diff --git a/.gitignore b/.gitignore index c6587a5..dae35a9 100644 --- a/.gitignore +++ b/.gitignore @@ -8,3 +8,9 @@ cache/ *.log *.svg *.gv + +traces/ +venv310/ +**/build/ +**/install/ +**/log/ \ No newline at end of file diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..4f1aa19 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,6 @@ +[submodule "dependencies/src/ros2_tracing"] + path = dependencies/src/ros2_tracing + url = git@github.com:ros2/ros2_tracing.git +[submodule "dependencies/src/tracetools_analysis"] + path = dependencies/src/tracetools_analysis + url = git@gitlab.com:ros-tracing/tracetools_analysis.git diff --git a/dependencies/colcon_defaults.yaml b/dependencies/colcon_defaults.yaml new file mode 100644 index 0000000..628bd9b --- /dev/null +++ b/dependencies/colcon_defaults.yaml @@ -0,0 +1,11 @@ +{ + "build":{ + "symlink-install": true, + "cmake-args": [ + "-DCMAKE_BUILD_TYPE=RelWithDebInfo", + "-DCMAKE_EXPORT_COMPILE_COMMANDS=True", + # no tests + "-DBUILD_TESTING=OFF", + ], + } +} diff --git a/dependencies/src/ros2_tracing b/dependencies/src/ros2_tracing new file mode 160000 index 0000000..548634d --- /dev/null +++ b/dependencies/src/ros2_tracing @@ -0,0 +1 @@ +Subproject commit 548634dd2837d65c043436c8186614e924be5c6c diff --git a/dependencies/src/tracetools_analysis b/dependencies/src/tracetools_analysis new file mode 160000 index 0000000..838b972 --- /dev/null +++ b/dependencies/src/tracetools_analysis @@ -0,0 +1 @@ +Subproject commit 838b97200023a1be6f9bae32240ee4118a15b6b9 diff --git a/latency_graph/latency_graph_plots.py b/latency_graph/latency_graph_plots.py index dce6363..a085f1a 100644 --- a/latency_graph/latency_graph_plots.py +++ b/latency_graph/latency_graph_plots.py @@ -113,9 +113,9 @@ def plot_latency_graph_overview(lat_graph: lg.LatencyGraph, excl_node_patterns, input_nodes = [n.full_name for n in lvl_nodes if any(re.search(p, n.full_name) for p in input_node_patterns)] output_nodes = [n.full_name for n in lvl_nodes if any(re.search(p, n.full_name) for p in output_node_patterns)] - print(', '.join(map(lambda n: n, input_nodes))) - print(', '.join(map(lambda n: n, output_nodes))) - print(', '.join(map(lambda n: n.full_name, lvl_nodes))) + print("Input Nodes:", ', '.join(map(lambda n: n, input_nodes))) + print("Output Nodes:", ', '.join(map(lambda n: n, output_nodes))) + print("Intermediate Nodes:", ', '.join(map(lambda n: n.full_name, lvl_nodes))) def _collect_callbacks(n: lg.LGHierarchyLevel): callbacks = [] diff --git a/latency_graph/latency_graph_structure.py b/latency_graph/latency_graph_structure.py index c97e234..7b9edb8 100644 --- a/latency_graph/latency_graph_structure.py +++ b/latency_graph/latency_graph_structure.py @@ -221,7 +221,7 @@ class LatencyGraph: nodes_to_cbs[node] = set() nodes_to_cbs[node].add(cb) - print(f"[ENTKÄFERN] {ownerless_cbs} callbacks have no owner, filtering them out.") + print(f"[DEBUG] {ownerless_cbs} callbacks have no owner, filtering them out.") ################################################## # Find in/out topics for each callback diff --git a/message_tree/message_tree_algorithms.py b/message_tree/message_tree_algorithms.py index e0f0713..1159092 100644 --- a/message_tree/message_tree_algorithms.py +++ b/message_tree/message_tree_algorithms.py @@ -108,6 +108,8 @@ def build_dep_trees(end_topics, lat_graph, tr, excluded_path_patterns, time_limi end_topic: TrTopic print(f"====={end_topic.name}") + tree_count = 0 + pubs = end_topic.publishers for pub in pubs: msgs = list(pub.instances) @@ -115,6 +117,8 @@ def build_dep_trees(end_topics, lat_graph, tr, excluded_path_patterns, time_limi msg: TrPublishInstance tree = get_dep_tree(msg, lat_graph, tr, excluded_path_patterns, time_limit_s, exact_path=exact_path) all_trees.append(tree) + tree_count += 1 + print(f"Found {tree_count} trees for topic {end_topic.name}") return all_trees diff --git a/trace-analysis.ipynb b/trace-analysis.ipynb index 9716f54..e8c4136 100644 --- a/trace-analysis.ipynb +++ b/trace-analysis.ipynb @@ -2,7 +2,7 @@ "cells": [ { "cell_type": "code", - "execution_count": null, + "execution_count": 1, "metadata": { "collapsed": false }, @@ -37,11 +37,44 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 2, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "User Settings:\n", + " TRACING_WS_BUILD_PATH................... := /home/niklas/dataflow-analysis/dependencies/build\n", + " TR_PATH................................. := /home/niklas/dataflow-analysis/traces/full_topology_tracing-20250603152153/ust\n", + " OUT_PATH................................ := /home/niklas/dataflow-analysis/out\n", + " CACHING_ENABLED......................... := False\n", + " BW_ENABLED.............................. := False\n", + " BW_PATH................................. := /home/niklas/dataflow-analysis/path/to/messages.h5\n", + " CL_ENABLED.............................. := False\n", + " CL_PATH................................. := /path/to/code_analysis/output\n", + " DFG_ENABLED............................. := True\n", + " DFG_PLOT................................ := True\n", + " DFG_MAX_HIER_LEVEL...................... := 100\n", + " DFG_INPUT_NODE_PATTERNS................. := ^/input_\n", + " DFG_OUTPUT_NODE_PATTERNS................ := ^/output_\n", + " DFG_EXCL_NODE_PATTERNS.................. := ^/rviz2\n", + " E2E_ENABLED............................. := True\n", + " E2E_PLOT................................ := True\n", + " E2E_PLOT_TIMESTAMP...................... := 100\n", + " E2E_TIME_LIMIT_S........................ := 500\n", + " E2E_OUTPUT_TOPIC_PATTERNS............... := ^/output/\n", + " E2E_INPUT_TOPIC_PATTERNS................ := ^/input/\n", + " E2E_EXCL_PATH_PATTERNS.................. := ^/parameter_events\n", + " E2E_INCL_PATH_PATTERNS.................. := \n", + " E2E_EXACT_PATH.......................... := \n", + " DEBUG................................... := False\n", + " MANUAL_CACHE............................ := False\n" + ] + } + ], "source": [ "##################################################\n", "# User Settings\n", @@ -59,12 +92,12 @@ "\n", "# The path to the build folder of a ROS2 workspace that contains the\n", "# tracetools_read and tracetools_analysis folders.\n", - "TRACING_WS_BUILD_PATH = \"/path/to/tracing_ws/build\"\n", + "TRACING_WS_BUILD_PATH = \"/home/niklas/dataflow-analysis/dependencies/build\"\n", "\n", "# Path to trace directory (e.g. ~/.ros/my-trace/ust) or to a converted trace file.\n", "# Using the path \"/ust\" at the end is optional but greatly reduces processing time\n", "# if kernel traces are also present.\n", - "TR_PATH = \"/path/to/tracing/session-name/ust\"\n", + "TR_PATH = \"/home/niklas/dataflow-analysis/traces/full_topology_tracing-20250603152153/ust\"\n", "\n", "# Path to the folder all artifacts from this notebook are saved to.\n", "# This entails plots as well as data tables.\n", @@ -89,9 +122,9 @@ "\n", "# Whether to compute data flow graphs.\n", "# If you are only interested in E2E latencies, set this to False\n", - "DFG_ENABLED = False\n", + "DFG_ENABLED = True\n", "# Whether to plot data flow graphs (ignored if DFG_ENABLED is False)\n", - "DFG_PLOT = False\n", + "DFG_PLOT = True\n", "\n", "# The maximum node namespace hierarchy level to be plotted.\n", "# Top-level (1): e.g. /sensing, /control, etc.\n", @@ -100,10 +133,10 @@ "\n", "# RegEx pattern for nodes that shall be marked as system inputs\n", "# These will be plotted with a start arrow as known from automata diagrams\n", - "DFG_INPUT_NODE_PATTERNS = [r\"^/sensing\"]\n", + "DFG_INPUT_NODE_PATTERNS = [r\"^/input_\"]\n", "# RegEx pattern for nodes that shall be marked as system outputs\n", "# These will be plotted with a double border\n", - "DFG_OUTPUT_NODE_PATTERNS = [r\"^/control/external_cmd_converter\"]\n", + "DFG_OUTPUT_NODE_PATTERNS = [r\"^/output_\"]\n", "# RegEx for nodes which shall not be plotted in the DFG\n", "DFG_EXCL_NODE_PATTERNS = [r\"^/rviz2\"]\n", "\n", @@ -113,24 +146,23 @@ "E2E_PLOT = True\n", "# The index of the output message that shall be used in plots that visualize a specific\n", "# message dependency tree. This index has to be 0 <= n < #output messages\n", - "E2E_PLOT_TIMESTAMP = 1000\n", + "E2E_PLOT_TIMESTAMP = 100\n", "# E2E latency threshold. Every E2E latency higher than this is discarded.\n", "# Set this as low as comfortably possible to speed up calculations.\n", "# WARNING: If you set this too low (i.e. to E2E latencies that plausibly can happen)\n", "# your results will be wrong)\n", - "E2E_TIME_LIMIT_S = 2\n", + "E2E_TIME_LIMIT_S = 500\n", "\n", "# All topics containing any of these RegEx patterns are considered output topics in E2E latency calculations\n", "# E.g. r\"^/control/\" will cover all control topics\n", - "E2E_OUTPUT_TOPIC_PATTERNS = [r\"^/control/command/control_cmd$\"]\n", + "E2E_OUTPUT_TOPIC_PATTERNS = [r\"^/output/\"]\n", "# All topics containing any of these RegEx patterns are considered input topics in E2E latency calculations\n", "# E.g. r\"^/sensing/\" will cover all sensing topics\n", - "E2E_INPUT_TOPIC_PATTERNS = [r\"pointcloud\"]\n", + "E2E_INPUT_TOPIC_PATTERNS = [r\"^/input/\"]\n", "\n", "# E2E paths are uniquely identified by a string like \"/topic/1 -> void(Node1)(args1) -> /topic/2 -> void(Node2)(args2) -> void(Node2)(args3) -> ...\".\n", "# Certain patterns only occur in initial setup or in scenario switching and can be excluded via RegEx patterns here.\n", - "E2E_EXCL_PATH_PATTERNS = [r\"^/parameter_events\", \"hazard\", \"turn_indicator\", \"gear_cmd\", \"emergency_cmd\", \"emergency_state\",\n", - " \"external_cmd\", \"/control/operation_mode\"]\n", + "E2E_EXCL_PATH_PATTERNS = [r\"^/parameter_events\"]\n", "\n", "# To specify paths of interest, topic/callback name patterns that HAVE TO OCCUR in each E2E path can be specified as RegEx here.\n", "#E2E_INCL_PATH_PATTERNS = [\"BehaviorPathPlanner\", \"BehaviorVelocityPlanner\", \"pointcloud_preprocessor::Filter\", r\"^/sensing/.*?pointcloud\"]\n", @@ -138,35 +170,7 @@ "\n", "# If an exact path through the system is known, this variabe can be set to a list (order matters!) of all elements on the path.\n", "# The first item ist the one at the \"input end\" of the system, the last one the \"output end\".\n", - "E2E_EXACT_PATH = [\n", - " \"void(pointcloud_preprocessor::Filter)(sensor_msgs::msg::PointCloud2,pcl_msgs::msg::PointIndices)\",\n", - " \"/localization/util/downsample/pointcloud\",\n", - " \"void(NDTScanMatcher)(sensor_msgs::msg::PointCloud2)\",\n", - " \"/localization/pose_estimator/pose_with_covariance\",\n", - " \"void(EKFLocalizer)(geometry_msgs::msg::PoseWithCovarianceStamped)\",\n", - " \"void(EKFLocalizer)()\",\n", - " \"/localization/pose_twist_fusion_filter/kinematic_state\",\n", - " \"void(StopFilter)(nav_msgs::msg::Odometry)\",\n", - " \"/localization/kinematic_state\",\n", - " \"void(behavior_path_planner::BehaviorPathPlannerNode)(nav_msgs::msg::Odometry)\",\n", - " \"void(behavior_path_planner::BehaviorPathPlannerNode)()\",\n", - " \"/planning/scenario_planning/lane_driving/behavior_planning/path_with_lane_id\",\n", - " \"void(behavior_velocity_planner::BehaviorVelocityPlannerNode)(autoware_auto_planning_msgs::msg::PathWithLaneId)\",\n", - " \"/planning/scenario_planning/lane_driving/behavior_planning/path\",\n", - " \"void(ObstacleAvoidancePlanner)(autoware_auto_planning_msgs::msg::Path)\",\n", - " \"/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/trajectory\",\n", - " \"void(motion_planning::ObstacleStopPlannerNode)(autoware_auto_planning_msgs::msg::Trajectory)\",\n", - " \"/planning/scenario_planning/lane_driving/trajectory\",\n", - " \"void(ScenarioSelectorNode)(autoware_auto_planning_msgs::msg::Trajectory)\",\n", - " \"/planning/scenario_planning/scenario_selector/trajectory\",\n", - " \"void(motion_velocity_smoother::MotionVelocitySmootherNode)(autoware_auto_planning_msgs::msg::Trajectory)\",\n", - " \"/planning/scenario_planning/trajectory\",\n", - " \"void(autoware::motion::control::trajectory_follower_nodes::Controller)(autoware_auto_planning_msgs::msg::Trajectory)\",\n", - " \"void(autoware::motion::control::trajectory_follower_nodes::Controller)()\",\n", - " \"/control/trajectory_follower/control_cmd\",\n", - " \"void(vehicle_cmd_gate::VehicleCmdGate)(autoware_auto_control_msgs::msg::AckermannControlCommand)\",\n", - " \"/control/command/control_cmd\",\n", - "]\n", + "E2E_EXACT_PATH = []\n", "\n", "# For development purposes only. Leave this at False.\n", "DEBUG = False\n", @@ -215,7 +219,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 3, "metadata": { "collapsed": false }, @@ -247,11 +251,58 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 4, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[CACHE] Cache disabled for tr_objects.\n", + "found converted file: /home/niklas/dataflow-analysis/traces/full_topology_tracing-20250603152153/ust/converted\n", + " [100%] [Ros2Handler]\n", + "[TrContext] Processing ROS 2 objects from traces...\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + " ├─ Processing TrNodes: 100%|██████████| 16/16 [00:00<00:00, 189573.06it/s]\n", + " ├─ Processing TrPublishers: 100%|██████████| 48/48 [00:00<00:00, 352585.98it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[DEBUG] Duplicate Indices in id\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + " ├─ Processing TrSubscriptions: 100%|██████████| 31/31 [00:00<00:00, 183131.58it/s]\n", + " ├─ Processing TrTimers: 100%|██████████| 6/6 [00:00<00:00, 92521.41it/s]\n", + " ├─ Processing TrTimerNodeLinks: 100%|██████████| 6/6 [00:00<00:00, 107088.61it/s]\n", + " ├─ Processing TrSubscriptionObjects: 100%|██████████| 31/31 [00:00<00:00, 331692.41it/s]\n", + " ├─ Processing TrCallbackObjects: 100%|██████████| 133/133 [00:00<00:00, 617082.34it/s]\n", + " ├─ Processing TrCallbackSymbols: 100%|██████████| 133/133 [00:00<00:00, 238394.20it/s]\n", + " ├─ Processing TrPublishInstances: 100%|██████████| 20207/20207 [00:00<00:00, 268376.27it/s]\n", + " ├─ Processing TrCallbackInstances: 100%|██████████| 20311/20311 [00:00<00:00, 293063.09it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Done.\n" + ] + } + ], "source": [ "def _load_traces():\n", " file = load_file(TR_PATH)\n", @@ -284,11 +335,50 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 5, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "/camera/debayered................................................................................................................. | 499 msgs\n", + "/camera/geometric................................................................................................................. | 499 msgs\n", + "/camera/radiometric............................................................................................................... | 499 msgs\n", + "/flight/plan...................................................................................................................... | 3596 msgs\n", + "/input/baro/alt................................................................................................................... | 601 msgs\n", + "/input/camera/raw................................................................................................................. | 499 msgs\n", + "/input/gps/fix.................................................................................................................... | 703 msgs\n", + "/input/imu/data................................................................................................................... | 499 msgs\n", + "/input/lidar/scan................................................................................................................. | 998 msgs\n", + "/input/operator/commands.......................................................................................................... | 798 msgs\n", + "/output/camera/mapped............................................................................................................. | 499 msgs\n", + "/output/classifier/classification................................................................................................. | 499 msgs\n", + "/output/flight/cmd................................................................................................................ | 3595 msgs\n", + "/output/telemetry/radio........................................................................................................... | 2302 msgs\n", + "/parameter_events................................................................................................................. | 16 msgs\n", + "/rosout........................................................................................................................... | 0 msgs\n", + "/sensors/fused.................................................................................................................... | 1803 msgs\n", + "/telemetry/data................................................................................................................... | 2302 msgs\n", + "\n", + "[DEBUG] INPUT TOPICS\n", + "--[DEBUG] ^/input/ :/input/baro/alt.......................................................................... | 601 msgs\n", + "--[DEBUG] ^/input/ :/input/camera/raw........................................................................ | 499 msgs\n", + "--[DEBUG] ^/input/ :/input/gps/fix........................................................................... | 703 msgs\n", + "--[DEBUG] ^/input/ :/input/imu/data.......................................................................... | 499 msgs\n", + "--[DEBUG] ^/input/ :/input/lidar/scan........................................................................ | 998 msgs\n", + "--[DEBUG] ^/input/ :/input/operator/commands................................................................. | 798 msgs\n", + "\n", + "[DEBUG] OUTPUT TOPICS\n", + "--[DEBUG] ^/output/ :/output/camera/mapped.................................................................... | 499 msgs\n", + "--[DEBUG] ^/output/ :/output/classifier/classification........................................................ | 499 msgs\n", + "--[DEBUG] ^/output/ :/output/flight/cmd....................................................................... | 3595 msgs\n", + "--[DEBUG] ^/output/ :/output/telemetry/radio.................................................................. | 2302 msgs\n" + ] + } + ], "source": [ "##################################################\n", "# Print (All/Input/Output) Topic Message Counts\n", @@ -323,11 +413,43 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 6, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[CACHE] Cache disabled for lat_graph.\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Finding CB nodes: 100%|██████████| 133/133 [00:00<00:00, 299111.22it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "[DEBUG] 96 callbacks have no owner, filtering them out.\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Processing node publications: 100%|██████████| 16/16 [00:00<00:00, 278.22it/s]\n", + "Processing CB subscriptions: 100%|██████████| 37/37 [00:00<00:00, 615.30it/s]\n", + "Building graph edges: 100%|██████████| 18/18 [00:00<00:00, 160975.42it/s]\n", + "Building graph nodes: 100%|██████████| 37/37 [00:00<00:00, 2422.60it/s]\n" + ] + } + ], "source": [ "import latency_graph.latency_graph_structure as lg\n", "\n", @@ -351,11 +473,595 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 7, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + " Processing INPUT: 1\n", + " Processing OUTPUT: 1\n", + " Processing input_camera_node: 2\n", + " Processing debayer_node: 2\n", + " Processing radiometric_node: 2\n", + " Processing geometric_node: 2\n", + " Processing output_mapping_node: 2\n", + " Processing output_smoke_classifier_node: 2\n", + " Processing input_gps_node: 2\n", + " Processing input_imu_node: 2\n", + " Processing input_baro_node: 2\n", + " Processing sensor_fusion_node: 4\n", + " Processing input_lidar_node: 2\n", + " Processing input_operator_cmd_node: 2\n", + " Processing flight_mgmt_node: 4\n", + " Processing output_flight_control_node: 2\n", + " Processing telemetry_node: 3\n", + " Processing output_radio_tx_node: 2\n" + ] + }, + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "cluster___INPUT\n", + "\n", + "INPUT\n", + "\n", + "\n", + "cluster___OUTPUT\n", + "\n", + "OUTPUT\n", + "\n", + "\n", + "cluster___input_camera_node\n", + "\n", + "input_camera_node\n", + "\n", + "\n", + "cluster___debayer_node\n", + "\n", + "debayer_node\n", + "\n", + "\n", + "cluster___radiometric_node\n", + "\n", + "radiometric_node\n", + "\n", + "\n", + "cluster___geometric_node\n", + "\n", + "geometric_node\n", + "\n", + "\n", + "cluster___output_mapping_node\n", + "\n", + "output_mapping_node\n", + "\n", + "\n", + "cluster___output_smoke_classifier_node\n", + "\n", + "output_smoke_classifier_node\n", + "\n", + "\n", + "cluster___input_gps_node\n", + "\n", + "input_gps_node\n", + "\n", + "\n", + "cluster___input_imu_node\n", + "\n", + "input_imu_node\n", + "\n", + "\n", + "cluster___input_baro_node\n", + "\n", + "input_baro_node\n", + "\n", + "\n", + "cluster___sensor_fusion_node\n", + "\n", + "sensor_fusion_node\n", + "\n", + "\n", + "cluster___input_lidar_node\n", + "\n", + "input_lidar_node\n", + "\n", + "\n", + "cluster___input_operator_cmd_node\n", + "\n", + "input_operator_cmd_node\n", + "\n", + "\n", + "cluster___flight_mgmt_node\n", + "\n", + "flight_mgmt_node\n", + "\n", + "\n", + "cluster___output_flight_control_node\n", + "\n", + "output_flight_control_node\n", + "\n", + "\n", + "cluster___telemetry_node\n", + "\n", + "telemetry_node\n", + "\n", + "\n", + "cluster___output_radio_tx_node\n", + "\n", + "output_radio_tx_node\n", + "\n", + "\n", + "\n", + "INPUT\n", + "\n", + "\n", + "INPUT\n", + "\n", + "\n", + "\n", + "\n", + "OUTPUT\n", + "\n", + "\n", + "OUTPUT\n", + "\n", + "\n", + "\n", + "\n", + "187650647101952\n", + "\n", + "\n", + "void(CameraNode::CameraNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))()\n", + "\n", + "\n", + "\n", + "\n", + "187650647327232\n", + "\n", + "\n", + "void(DebayerNode::DebayerNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650647101952:out->187650647327232:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650647093888\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650647510848\n", + "\n", + "\n", + "void(RadiometricNode::RadiometricNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650647327232:out->187650647510848:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650647317664\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650647733456\n", + "\n", + "\n", + "void(GeometricNode::GeometricNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650647510848:out->187650647733456:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648131424\n", + "\n", + "\n", + "void(SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650647510848:out->187650648131424:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650647492400\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650647372752\n", + "\n", + "\n", + "void(MappingNode::MappingNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650647733456:out->187650647372752:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650647690704\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650647886896\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650649967104\n", + "\n", + "\n", + "void(TelemetryNode::TelemetryNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650647372752:out->187650649967104:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648096592\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650648296336\n", + "\n", + "\n", + "void(GPSNode::GPSNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))()\n", + "\n", + "\n", + "\n", + "\n", + "187650648938336\n", + "\n", + "\n", + "void(FusionNode::FusionNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650648296336:out->187650648938336:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648289664\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650647921232\n", + "\n", + "\n", + "void(IMUNode::IMUNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))()\n", + "\n", + "\n", + "\n", + "\n", + "187650648922448\n", + "\n", + "\n", + "void(FusionNode::FusionNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650647921232:out->187650648922448:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648494000\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650648702544\n", + "\n", + "\n", + "void(BaroNode::BaroNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))()\n", + "\n", + "\n", + "\n", + "\n", + "187650648913568\n", + "\n", + "\n", + "void(FusionNode::FusionNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650648702544:out->187650648913568:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648695248\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650649500800\n", + "\n", + "\n", + "void(FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650648913568:out->187650649500800:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649956624\n", + "\n", + "\n", + "void(TelemetryNode::TelemetryNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650648913568:out->187650649956624:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648922448:out->187650649500800:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648922448:out->187650649956624:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648925776\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650648938336:out->187650649500800:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650648938336:out->187650649956624:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649139808\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650649112976\n", + "\n", + "\n", + "void(LidarNode::LidarNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))()\n", + "\n", + "\n", + "\n", + "\n", + "187650649524848\n", + "\n", + "\n", + "void(FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650649112976:out->187650649524848:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649330112\n", + "\n", + "\n", + "void(CommandNode::CommandNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))()\n", + "\n", + "\n", + "\n", + "\n", + "187650649503456\n", + "\n", + "\n", + "void(FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::vector<std::__cxx11::basic_string<char,std::char_traits<char>,>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650649330112:out->187650649503456:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649303984\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650648522864\n", + "\n", + "\n", + "void(ControlNode::ControlNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650649503456:out->187650648522864:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649497136\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650649500800:out->187650648522864:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649524848:out->187650648522864:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649726160\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650650156944\n", + "\n", + "\n", + "void(RadioNode::RadioNode(std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,std::__cxx11::basic_string<char,std::char_traits<char>,>,int,double))(std_msgs::msg::String)\n", + "\n", + "\n", + "\n", + "\n", + "187650649956624:out->187650650156944:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649967104:out->187650650156944:in\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "187650649970080\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n", + "187650650138992\n", + "\n", + "\n", + "void(rclcpp::TimeSource)(rcl_interfaces::msg::ParameterEvent)\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "execution_count": 7, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "%%skip_if_false DFG_ENABLED\n", "%%skip_if_false DFG_PLOT\n", @@ -381,14 +1087,330 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 8, "metadata": { "collapsed": false, "pycharm": { "name": "#%%%%skip_if_false DFG_ENABLED\n" } }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Plotting DFG overview with max hierarchy level 100...\n", + "Input Node Patterns: ['^/input_']\n", + "Output Node Patterns: ['^/output_']\n", + "Excluded Node Patterns: ['^/rviz2']\n", + "Input Nodes: /input_camera_node, /input_gps_node, /input_imu_node, /input_baro_node, /input_lidar_node, /input_operator_cmd_node\n", + "Output Nodes: /output_mapping_node, /output_smoke_classifier_node, /output_flight_control_node, /output_radio_tx_node\n", + "Intermediate Nodes: /INPUT, /OUTPUT, /input_camera_node, /debayer_node, /radiometric_node, /geometric_node, /output_mapping_node, /output_smoke_classifier_node, /input_gps_node, /input_imu_node, /input_baro_node, /sensor_fusion_node, /input_lidar_node, /input_operator_cmd_node, /flight_mgmt_node, /output_flight_control_node, /telemetry_node, /output_radio_tx_node\n", + "/input_lidar_node /flight_mgmt_node 1\n", + "/input_gps_node /sensor_fusion_node 1\n", + "/input_operator_cmd_node /flight_mgmt_node 1\n", + "/debayer_node /radiometric_node 1\n", + "/radiometric_node /geometric_node 1\n", + "/radiometric_node /output_smoke_classifier_node 1\n", + "/input_baro_node /sensor_fusion_node 1\n", + "/flight_mgmt_node /output_flight_control_node 3\n", + "/input_camera_node /debayer_node 1\n", + "/output_mapping_node /telemetry_node 1\n", + "/telemetry_node /output_radio_tx_node 2\n", + "/sensor_fusion_node /telemetry_node 3\n", + "/sensor_fusion_node /flight_mgmt_node 3\n", + "/input_imu_node /sensor_fusion_node 1\n", + "/geometric_node /output_mapping_node 1\n" + ] + }, + { + "data": { + "image/svg+xml": [ + "\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "G\n", + "\n", + "\n", + "\n", + "/INPUT\n", + "\n", + "/INPUT\n", + "\n", + "\n", + "\n", + "/OUTPUT\n", + "\n", + "/OUTPUT\n", + "\n", + "\n", + "\n", + "/input_camera_node\n", + "\n", + "/input_camera_node\n", + "\n", + "\n", + "\n", + "/debayer_node\n", + "\n", + "/debayer_node\n", + "\n", + "\n", + "\n", + "/input_camera_node->/debayer_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_camera_node__before\n", + "\n", + "\n", + "\n", + "/input_camera_node__before->/input_camera_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/radiometric_node\n", + "\n", + "/radiometric_node\n", + "\n", + "\n", + "\n", + "/debayer_node->/radiometric_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/geometric_node\n", + "\n", + "/geometric_node\n", + "\n", + "\n", + "\n", + "/radiometric_node->/geometric_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/output_smoke_classifier_node\n", + "\n", + "\n", + "/output_smoke_classifier_node\n", + "\n", + "\n", + "\n", + "/radiometric_node->/output_smoke_classifier_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/output_mapping_node\n", + "\n", + "\n", + "/output_mapping_node\n", + "\n", + "\n", + "\n", + "/geometric_node->/output_mapping_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/telemetry_node\n", + "\n", + "/telemetry_node\n", + "\n", + "\n", + "\n", + "/output_mapping_node->/telemetry_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_gps_node\n", + "\n", + "/input_gps_node\n", + "\n", + "\n", + "\n", + "/sensor_fusion_node\n", + "\n", + "/sensor_fusion_node\n", + "\n", + "\n", + "\n", + "/input_gps_node->/sensor_fusion_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_gps_node__before\n", + "\n", + "\n", + "\n", + "/input_gps_node__before->/input_gps_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_imu_node\n", + "\n", + "/input_imu_node\n", + "\n", + "\n", + "\n", + "/input_imu_node->/sensor_fusion_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_imu_node__before\n", + "\n", + "\n", + "\n", + "/input_imu_node__before->/input_imu_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_baro_node\n", + "\n", + "/input_baro_node\n", + "\n", + "\n", + "\n", + "/input_baro_node->/sensor_fusion_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_baro_node__before\n", + "\n", + "\n", + "\n", + "/input_baro_node__before->/input_baro_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/flight_mgmt_node\n", + "\n", + "/flight_mgmt_node\n", + "\n", + "\n", + "\n", + "/sensor_fusion_node->/flight_mgmt_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/sensor_fusion_node->/telemetry_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_lidar_node\n", + "\n", + "/input_lidar_node\n", + "\n", + "\n", + "\n", + "/input_lidar_node->/flight_mgmt_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_lidar_node__before\n", + "\n", + "\n", + "\n", + "/input_lidar_node__before->/input_lidar_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_operator_cmd_node\n", + "\n", + "/input_operator_cmd_node\n", + "\n", + "\n", + "\n", + "/input_operator_cmd_node->/flight_mgmt_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/input_operator_cmd_node__before\n", + "\n", + "\n", + "\n", + "/input_operator_cmd_node__before->/input_operator_cmd_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/output_flight_control_node\n", + "\n", + "\n", + "/output_flight_control_node\n", + "\n", + "\n", + "\n", + "/flight_mgmt_node->/output_flight_control_node\n", + "\n", + "\n", + "\n", + "\n", + "\n", + "/output_radio_tx_node\n", + "\n", + "\n", + "/output_radio_tx_node\n", + "\n", + "\n", + "\n", + "/telemetry_node->/output_radio_tx_node\n", + "\n", + "\n", + "\n", + "\n", + "\n" + ], + "text/plain": [ + "" + ] + }, + "execution_count": 8, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "%%skip_if_false DFG_ENABLED\n", "%%skip_if_false DFG_PLOT\n", @@ -400,6 +1422,11 @@ "\n", "from latency_graph.latency_graph_plots import plot_latency_graph_overview\n", "\n", + "print(f\"Plotting DFG overview with max hierarchy level {DFG_MAX_HIER_LEVEL}...\")\n", + "print(f\"Input Node Patterns: {DFG_INPUT_NODE_PATTERNS}\")\n", + "print(f\"Output Node Patterns: {DFG_OUTPUT_NODE_PATTERNS}\")\n", + "print(f\"Excluded Node Patterns: {DFG_EXCL_NODE_PATTERNS}\")\n", + "\n", "plot_latency_graph_overview(lat_graph, DFG_EXCL_NODE_PATTERNS, DFG_INPUT_NODE_PATTERNS, DFG_OUTPUT_NODE_PATTERNS, DFG_MAX_HIER_LEVEL, os.path.join(OUT_PATH, \"latency_graph_overview\"))" ] }, @@ -415,11 +1442,88 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 9, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 4 end topics for E2E latency calculations: /output/telemetry/radio, /output/camera/mapped, /output/classifier/classification, /output/flight/cmd\n", + "Using 133 callback objects, 20311 callback instances, and 20207 publish instances for E2E latency calculations.\n", + "[CACHE] Cache disabled for trees.\n", + "=====/output/telemetry/radio\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Processing output messages: 100%|██████████| 2302/2302 [00:11<00:00, 203.94it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 2302 trees for topic /output/telemetry/radio\n", + "=====/output/camera/mapped\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Processing output messages: 100%|██████████| 499/499 [00:00<00:00, 7355.95it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 499 trees for topic /output/camera/mapped\n", + "=====/output/classifier/classification\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Processing output messages: 100%|██████████| 499/499 [00:00<00:00, 1005.12it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 499 trees for topic /output/classifier/classification\n", + "=====/output/flight/cmd\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Processing output messages: 100%|██████████| 3595/3595 [00:09<00:00, 360.81it/s]" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 3595 trees for topic /output/flight/cmd\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "\n" + ] + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "\n", @@ -427,8 +1531,13 @@ "\n", "end_topics = [t for t in _tracing_context.topics if any(re.search(f, t.name) for f in E2E_OUTPUT_TOPIC_PATTERNS)]\n", "\n", + "print(f\"Found {len(end_topics)} end topics for E2E latency calculations: {', '.join(t.name for t in end_topics)}\")\n", + "\n", + "print(f\"Using {len(_tracing_context.callback_objects)} callback objects, {len(_tracing_context.callback_instances)} callback instances, and {len(_tracing_context.publish_instances)} publish instances for E2E latency calculations.\")\n", + "\n", "def _build_dep_trees():\n", - " return build_dep_trees(end_topics, lat_graph, _tracing_context, E2E_EXCL_PATH_PATTERNS, E2E_TIME_LIMIT_S, exact_path=E2E_EXACT_PATH)\n", + " return build_dep_trees(end_topics, lat_graph, _tracing_context, E2E_EXCL_PATH_PATTERNS, E2E_TIME_LIMIT_S)\n", + " #return build_dep_trees(end_topics, lat_graph, _tracing_context, E2E_EXCL_PATH_PATTERNS, E2E_TIME_LIMIT_S, exact_path=E2E_EXACT_PATH)\n", "\n", "try:\n", " trees = cached(\"trees\", _build_dep_trees, [TR_PATH], not CACHING_ENABLED)\n", @@ -440,11 +1549,22 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 10, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "data": { + "text/plain": [ + "'Skipped (evaluated BW_ENABLED to False)'" + ] + }, + "execution_count": 10, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "%%skip_if_false BW_ENABLED\n", @@ -463,33 +1583,164474 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 11, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Dependency Trees:\n", + "\n", + "Tree 1/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 7/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 8/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 9/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 10/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 11/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 12/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 13/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 14/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 15/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 16/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 17/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 18/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 19/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 20/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 21/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 22/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 23/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 24/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 25/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 26/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 27/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 28/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 29/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 30/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 31/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 32/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 33/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 34/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 35/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 36/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 37/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 38/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 39/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 40/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 41/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 42/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 43/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 44/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 45/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 46/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 47/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 48/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 49/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 50/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 51/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 52/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 53/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 54/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 55/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 56/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 57/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 58/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 59/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 60/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 61/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 62/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 63/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 64/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 65/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 66/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 67/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 68/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 69/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 70/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 71/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 72/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 73/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 74/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 75/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 76/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 77/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 78/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 79/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 80/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 81/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 82/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 83/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 84/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 85/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 86/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 87/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 88/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 89/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 90/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 91/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 92/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 93/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 94/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 95/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 96/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 97/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 98/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 99/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 100/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 101/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 102/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 103/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 104/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 105/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 106/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 107/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 108/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 109/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 110/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 111/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 112/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 113/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 114/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 115/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 116/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 117/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 118/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 119/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 120/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 121/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 122/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 123/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 124/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 125/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 126/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 127/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 128/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 129/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 130/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 131/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 132/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 133/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 134/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 135/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 136/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 137/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 138/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 139/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 140/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 141/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 142/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 143/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 144/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 145/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 146/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 147/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 148/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 149/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 150/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 151/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 152/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 153/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 154/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 155/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 156/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 157/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 158/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 159/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 160/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 161/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 162/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 163/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 164/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 165/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 166/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 167/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 168/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 169/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 170/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 171/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 172/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 173/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 174/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 175/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 176/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 177/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 178/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 179/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 180/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 181/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 182/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 183/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 184/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 185/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 186/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 187/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 188/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 189/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 190/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 191/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 192/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 193/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 194/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 195/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 196/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 197/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 198/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 199/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 200/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 201/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 202/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 203/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 204/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 205/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 206/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 207/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 208/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 209/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 210/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 211/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 212/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 213/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 214/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 215/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 216/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 217/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 218/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 219/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 220/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 221/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 222/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 223/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 224/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 225/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 226/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 227/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 228/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 229/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 230/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 231/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 232/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 233/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 234/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 235/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 236/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 237/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 238/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 239/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 240/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 241/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 242/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 243/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 244/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 245/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 246/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 247/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 248/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 249/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 250/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 251/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 252/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 253/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 254/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 255/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 256/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 257/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 258/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 259/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 260/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 261/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 262/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 263/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 264/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 265/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 266/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 267/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 268/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 269/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 270/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 271/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 272/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 273/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 274/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 275/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 276/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 277/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 278/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 279/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 280/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 281/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 282/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 283/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 284/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 285/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 286/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 287/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 288/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 289/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 290/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 291/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 292/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 293/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 294/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 295/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 296/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 297/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 298/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 299/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 300/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 301/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 302/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 303/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 304/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 305/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 306/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 307/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 308/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 309/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 310/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 311/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 312/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 313/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 314/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 315/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 316/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 317/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 318/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 319/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 320/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 321/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 322/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 323/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 324/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 325/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 326/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 327/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 328/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 329/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 330/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 331/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 332/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 333/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 334/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 335/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 336/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 337/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 338/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 339/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 340/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 341/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 342/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 343/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 344/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 345/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 346/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 347/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 348/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 349/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 350/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 351/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 352/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 353/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 354/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 355/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 356/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 357/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 358/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 359/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 360/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 361/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 362/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 363/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 364/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 365/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 366/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 367/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 368/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 369/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 370/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 371/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 372/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 373/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 374/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 375/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 376/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 377/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 378/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 379/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 380/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 381/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 382/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 383/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 384/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 385/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 386/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 387/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 388/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 389/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 390/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 391/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 392/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 393/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 394/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 395/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 396/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 397/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 398/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 399/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 400/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 401/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 402/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 403/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 404/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 405/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 406/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 407/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 408/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 409/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 410/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 411/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 412/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 413/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 414/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 415/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 416/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 417/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 418/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 419/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 420/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 421/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 422/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 423/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 424/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 425/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 426/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 427/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 428/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 429/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 430/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 431/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 432/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 433/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 434/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 435/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 436/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 437/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 438/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 439/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 440/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 441/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 442/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 443/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 444/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 445/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 446/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 447/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 448/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 449/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 450/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 451/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 452/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 453/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 454/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 455/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 456/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 457/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 458/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 459/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 460/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 461/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 462/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 463/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 464/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 465/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 466/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 467/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 468/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 469/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 470/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 471/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 472/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 473/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 474/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 475/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 476/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 477/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 478/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 479/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 480/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 481/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 482/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 483/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 484/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 485/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 486/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 487/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 488/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 489/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 490/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 491/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 492/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 493/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 494/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 495/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 496/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 497/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 498/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 499/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 500/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 501/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 502/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 503/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 504/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 505/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 506/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 507/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 508/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 509/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 510/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 511/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 512/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 513/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 514/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 515/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 516/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 517/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 518/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 519/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 520/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 521/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 522/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 523/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 524/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 525/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 526/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 527/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 528/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 529/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 530/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 531/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 532/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 533/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 534/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 535/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 536/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 537/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 538/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 539/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 540/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 541/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 542/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 543/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 544/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 545/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 546/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 547/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 548/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 549/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 550/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 551/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 552/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 553/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 554/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 555/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 556/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 557/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 558/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 559/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 560/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 561/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 562/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 563/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 564/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 565/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 566/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 567/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 568/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 569/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 570/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 571/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 572/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 573/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 574/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 575/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 576/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 577/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 578/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 579/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 580/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 581/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 582/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 583/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 584/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 585/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 586/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 587/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 588/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 589/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 590/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 591/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 592/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 593/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 594/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 595/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 596/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 597/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 598/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 599/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 600/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 601/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 602/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 603/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 604/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 605/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 606/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 607/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 608/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 609/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 610/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 611/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 612/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 613/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 614/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 615/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 616/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 617/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 618/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 619/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 620/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 621/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 622/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 623/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 624/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 625/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 626/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 627/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 628/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 629/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 630/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 631/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 632/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 633/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 634/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 635/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 636/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 637/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 638/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 639/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 640/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 641/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 642/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 643/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 644/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 645/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 646/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 647/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 648/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 649/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 650/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 651/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 652/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 653/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 654/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 655/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 656/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 657/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 658/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 659/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 660/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 661/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 662/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 663/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 664/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 665/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 666/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 667/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 668/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 669/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 670/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 671/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 672/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 673/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 674/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 675/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 676/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 677/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 678/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 679/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 680/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 681/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 682/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 683/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 684/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 685/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 686/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 687/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 688/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 689/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 690/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 691/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 692/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 693/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 694/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 695/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 696/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 697/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 698/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 699/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 700/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 701/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 702/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 703/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 704/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 705/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 706/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 707/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 708/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 709/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 710/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 711/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 712/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 713/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 714/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 715/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 716/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 717/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 718/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 719/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 720/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 721/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 722/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 723/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 724/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 725/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 726/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 727/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 728/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 729/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 730/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 731/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 732/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 733/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 734/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 735/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 736/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 737/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 738/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 739/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 740/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 741/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 742/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 743/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 744/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 745/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 746/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 747/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 748/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 749/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 750/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 751/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 752/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 753/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 754/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 755/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 756/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 757/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 758/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 759/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 760/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 761/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 762/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 763/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 764/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 765/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 766/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 767/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 768/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 769/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 770/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 771/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 772/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 773/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 774/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 775/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 776/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 777/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 778/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 779/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 780/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 781/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 782/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 783/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 784/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 785/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 786/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 787/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 788/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 789/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 790/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 791/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 792/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 793/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 794/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 795/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 796/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 797/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 798/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 799/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 800/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 801/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 802/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 803/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 804/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 805/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 806/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 807/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 808/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 809/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 810/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 811/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 812/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 813/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 814/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 815/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 816/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 817/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 818/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 819/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 820/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 821/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 822/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 823/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 824/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 825/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 826/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 827/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 828/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 829/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 830/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 831/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 832/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 833/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 834/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 835/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 836/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 837/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 838/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 839/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 840/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 841/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 842/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 843/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 844/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 845/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 846/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 847/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 848/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 849/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 850/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 851/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 852/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 853/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 854/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 855/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 856/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 857/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 858/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 859/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 860/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 861/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 862/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 863/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 864/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 865/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 866/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 867/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 868/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 869/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 870/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 871/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 872/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 873/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 874/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 875/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 876/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 877/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 878/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 879/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 880/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 881/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 882/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 883/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 884/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 885/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 886/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 887/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 888/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 889/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 890/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 891/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 892/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 893/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 894/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 895/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 896/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 897/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 898/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 899/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 900/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 901/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 902/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 903/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 904/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 905/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 906/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 907/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 908/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 909/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 910/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 911/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 912/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 913/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 914/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 915/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 916/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 917/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 918/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 919/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 920/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 921/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 922/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 923/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 924/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 925/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 926/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 927/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 928/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 929/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 930/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 931/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 932/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 933/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 934/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 935/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 936/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 937/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 938/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 939/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 940/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 941/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 942/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 943/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 944/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 945/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 946/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 947/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 948/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 949/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 950/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 951/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 952/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 953/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 954/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 955/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 956/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 957/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 958/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 959/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 960/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 961/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 962/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 963/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 964/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 965/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 966/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 967/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 968/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 969/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 970/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 971/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 972/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 973/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 974/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 975/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 976/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 977/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 978/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 979/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 980/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 981/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 982/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 983/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 984/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 985/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 986/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 987/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 988/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 989/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 990/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 991/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 992/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 993/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 994/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 995/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 996/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 997/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 998/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 999/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1000/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1001/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1002/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1003/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1004/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1005/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1006/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1007/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1008/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1009/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1010/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1011/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1012/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1013/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1014/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1015/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1016/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1017/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1018/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1019/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1020/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1021/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1022/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1023/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1024/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1025/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1026/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1027/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1028/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1029/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1030/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1031/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1032/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1033/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1034/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1035/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1036/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1037/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1038/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1039/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1040/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1041/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1042/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1043/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1044/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1045/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1046/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1047/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1048/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1049/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1050/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1051/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1052/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1053/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1054/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1055/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1056/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1057/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1058/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1059/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1060/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1061/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1062/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1063/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1064/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1065/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1066/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1067/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1068/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1069/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1070/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1071/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1072/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1073/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1074/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1075/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1076/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1077/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1078/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1079/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1080/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1081/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1082/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1083/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1084/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1085/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1086/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1087/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1088/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1089/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1090/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1091/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1092/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1093/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1094/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1095/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1096/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1097/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1098/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1099/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1100/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1101/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1102/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1103/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1104/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1105/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1106/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1107/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1108/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1109/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1110/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1111/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1112/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1113/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1114/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1115/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1116/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1117/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1118/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1119/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1120/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1121/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1122/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1123/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1124/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1125/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1126/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1127/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1128/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1129/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1130/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1131/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1132/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1133/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1134/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1135/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1136/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1137/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1138/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1139/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1140/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1141/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1142/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1143/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1144/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1145/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1146/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1147/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1148/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1149/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1150/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1151/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1152/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1153/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1154/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1155/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1156/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1157/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1158/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1159/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1160/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1161/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1162/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1163/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1164/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1165/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1166/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1167/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1168/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1169/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1170/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1171/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1172/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1173/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1174/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1175/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1176/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1177/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1178/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1179/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1180/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1181/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1182/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1183/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1184/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1185/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1186/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1187/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1188/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1189/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1190/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1191/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1192/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1193/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1194/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1195/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1196/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1197/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1198/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1199/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1200/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1201/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1202/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1203/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1204/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1205/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1206/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1207/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1208/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1209/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1210/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1211/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1212/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1213/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1214/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1215/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1216/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1217/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1218/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1219/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1220/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1221/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1222/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1223/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1224/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1225/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1226/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1227/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1228/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1229/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1230/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1231/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1232/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1233/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1234/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1235/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1236/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1237/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1238/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1239/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1240/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1241/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1242/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1243/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1244/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1245/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1246/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1247/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1248/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1249/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1250/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1251/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1252/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1253/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1254/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1255/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1256/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1257/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1258/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1259/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1260/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1261/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1262/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1263/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1264/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1265/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1266/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1267/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1268/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1269/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1270/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1271/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1272/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1273/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1274/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1275/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1276/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1277/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1278/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1279/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1280/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1281/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1282/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1283/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1284/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1285/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1286/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1287/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1288/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1289/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1290/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1291/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1292/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1293/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1294/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1295/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1296/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1297/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1298/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1299/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1300/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1301/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1302/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1303/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1304/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1305/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1306/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1307/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1308/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1309/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1310/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1311/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1312/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1313/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1314/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1315/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1316/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1317/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1318/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1319/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1320/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1321/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1322/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1323/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1324/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1325/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1326/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1327/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1328/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1329/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1330/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1331/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1332/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1333/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1334/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1335/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1336/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1337/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1338/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1339/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1340/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1341/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1342/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1343/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1344/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1345/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1346/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1347/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1348/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1349/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1350/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1351/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1352/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1353/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1354/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1355/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1356/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1357/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1358/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1359/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1360/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1361/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1362/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1363/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1364/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1365/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1366/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1367/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1368/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1369/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1370/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1371/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1372/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1373/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1374/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1375/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1376/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1377/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1378/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1379/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1380/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1381/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1382/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1383/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1384/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1385/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1386/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1387/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1388/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1389/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1390/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1391/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1392/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1393/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1394/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1395/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1396/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1397/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1398/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1399/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1400/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1401/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1402/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1403/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1404/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1405/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1406/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1407/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1408/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1409/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1410/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1411/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1412/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1413/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1414/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1415/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1416/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1417/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1418/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1419/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1420/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1421/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1422/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1423/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1424/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1425/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1426/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1427/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1428/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1429/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1430/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1431/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1432/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1433/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1434/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1435/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1436/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1437/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1438/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1439/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1440/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1441/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1442/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1443/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1444/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1445/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1446/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1447/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1448/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1449/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1450/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1451/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1452/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1453/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1454/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1455/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1456/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1457/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1458/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1459/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1460/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1461/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1462/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1463/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1464/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1465/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1466/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1467/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1468/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1469/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1470/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1471/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1472/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1473/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1474/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1475/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1476/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1477/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1478/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1479/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1480/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1481/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1482/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1483/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1484/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1485/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1486/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1487/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1488/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1489/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1490/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1491/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1492/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1493/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1494/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1495/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1496/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1497/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1498/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1499/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1500/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1501/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1502/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1503/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1504/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1505/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1506/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1507/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1508/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1509/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1510/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1511/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1512/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1513/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1514/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1515/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1516/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1517/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1518/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1519/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1520/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1521/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1522/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1523/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1524/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1525/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1526/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1527/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1528/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1529/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1530/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1531/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1532/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1533/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1534/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1535/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1536/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1537/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1538/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1539/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1540/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1541/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1542/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1543/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1544/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1545/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1546/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1547/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1548/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1549/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1550/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1551/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1552/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1553/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1554/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1555/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1556/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1557/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1558/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1559/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1560/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1561/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1562/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1563/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1564/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1565/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1566/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1567/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1568/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1569/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1570/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1571/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1572/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1573/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1574/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1575/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1576/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1577/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1578/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1579/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1580/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1581/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1582/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1583/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1584/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1585/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1586/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1587/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1588/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1589/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1590/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1591/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1592/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1593/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1594/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1595/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1596/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1597/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1598/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1599/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1600/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1601/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1602/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1603/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1604/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1605/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1606/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1607/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1608/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1609/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1610/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1611/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1612/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1613/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1614/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1615/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1616/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1617/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1618/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1619/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1620/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1621/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1622/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1623/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1624/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1625/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1626/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1627/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1628/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1629/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1630/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1631/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1632/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1633/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1634/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1635/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1636/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1637/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1638/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1639/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1640/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1641/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1642/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1643/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1644/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1645/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1646/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1647/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1648/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1649/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1650/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1651/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1652/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1653/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1654/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1655/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1656/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1657/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1658/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1659/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1660/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1661/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1662/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1663/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1664/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1665/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1666/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1667/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1668/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1669/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1670/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1671/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1672/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1673/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1674/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1675/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1676/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1677/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1678/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1679/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1680/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1681/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1682/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1683/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1684/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1685/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1686/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1687/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1688/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1689/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1690/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1691/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1692/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1693/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1694/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1695/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1696/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1697/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1698/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1699/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1700/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1701/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1702/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1703/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1704/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1705/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1706/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1707/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1708/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1709/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1710/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1711/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1712/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1713/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1714/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1715/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1716/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1717/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1718/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1719/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1720/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1721/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1722/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1723/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1724/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1725/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1726/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1727/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1728/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1729/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1730/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1731/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1732/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1733/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1734/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1735/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1736/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1737/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1738/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1739/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1740/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1741/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1742/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1743/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1744/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1745/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1746/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1747/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1748/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1749/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1750/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1751/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1752/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1753/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1754/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1755/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1756/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1757/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1758/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1759/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1760/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1761/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1762/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1763/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1764/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1765/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1766/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1767/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1768/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1769/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1770/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1771/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1772/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1773/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1774/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1775/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1776/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1777/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1778/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1779/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1780/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1781/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1782/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1783/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1784/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1785/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1786/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1787/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1788/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1789/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1790/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1791/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1792/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1793/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1794/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1795/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1796/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1797/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1798/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1799/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1800/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1801/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1802/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1803/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1804/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1805/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1806/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1807/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1808/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1809/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1810/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1811/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1812/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1813/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1814/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1815/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1816/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1817/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1818/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1819/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1820/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1821/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1822/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1823/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1824/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1825/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1826/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1827/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1828/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1829/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1830/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1831/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1832/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1833/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1834/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1835/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1836/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1837/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1838/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1839/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1840/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1841/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1842/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1843/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1844/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1845/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1846/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1847/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1848/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1849/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1850/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1851/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1852/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1853/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1854/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1855/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1856/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1857/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1858/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1859/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1860/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1861/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1862/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1863/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1864/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1865/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1866/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1867/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1868/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1869/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1870/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1871/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1872/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1873/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1874/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1875/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1876/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1877/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1878/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1879/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1880/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1881/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1882/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1883/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1884/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1885/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1886/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1887/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1888/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1889/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1890/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1891/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1892/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1893/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1894/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1895/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1896/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1897/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1898/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1899/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1900/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1901/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1902/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1903/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1904/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1905/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1906/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1907/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1908/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1909/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1910/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1911/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1912/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1913/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1914/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1915/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1916/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1917/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1918/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1919/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1920/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1921/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1922/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1923/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1924/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1925/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1926/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1927/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1928/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1929/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1930/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1931/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1932/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1933/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1934/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1935/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1936/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1937/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1938/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1939/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1940/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1941/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1942/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1943/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1944/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1945/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1946/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1947/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1948/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1949/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1950/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1951/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1952/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1953/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1954/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1955/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1956/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1957/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1958/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1959/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1960/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1961/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1962/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1963/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1964/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1965/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1966/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1967/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1968/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1969/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1970/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1971/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1972/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1973/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1974/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1975/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1976/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1977/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1978/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1979/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1980/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1981/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1982/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1983/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1984/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1985/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1986/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1987/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1988/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1989/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1990/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1991/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1992/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1993/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1994/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1995/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1996/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1997/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1998/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 1999/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2000/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2001/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2002/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2003/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2004/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2005/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2006/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2007/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2008/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2009/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2010/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2011/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2012/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2013/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2014/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2015/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2016/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2017/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2018/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2019/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2020/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2021/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2022/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2023/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2024/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2025/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2026/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2027/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2028/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2029/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2030/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2031/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2032/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2033/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2034/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2035/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2036/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2037/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2038/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2039/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2040/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2041/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2042/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2043/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2044/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2045/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2046/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2047/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2048/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2049/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2050/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2051/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2052/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2053/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2054/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2055/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2056/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2057/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2058/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2059/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2060/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2061/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2062/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2063/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2064/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2065/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2066/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2067/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2068/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2069/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2070/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2071/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2072/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2073/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2074/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2075/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2076/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2077/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2078/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2079/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2080/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2081/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2082/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2083/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2084/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2085/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2086/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2087/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2088/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2089/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2090/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2091/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2092/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2093/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2094/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2095/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2096/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2097/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2098/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2099/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2100/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2101/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2102/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2103/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2104/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2105/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2106/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2107/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2108/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2109/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2110/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2111/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2112/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2113/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2114/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2115/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2116/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2117/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2118/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2119/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2120/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2121/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2122/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2123/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2124/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2125/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2126/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2127/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2128/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2129/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2130/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2131/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2132/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2133/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2134/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2135/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2136/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2137/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2138/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2139/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2140/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2141/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2142/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2143/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2144/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2145/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2146/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2147/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2148/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2149/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2150/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2151/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2152/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2153/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2154/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2155/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2156/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2157/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2158/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2159/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2160/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2161/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2162/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2163/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2164/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2165/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2166/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2167/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2168/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2169/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2170/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2171/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2172/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2173/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2174/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2175/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2176/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2177/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2178/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2179/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2180/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2181/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2182/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2183/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2184/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2185/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2186/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2187/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2188/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2189/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2190/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2191/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2192/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2193/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2194/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2195/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2196/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2197/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2198/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2199/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2200/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2201/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2202/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2203/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2204/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2205/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2206/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2207/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2208/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2209/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2210/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2211/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2212/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2213/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2214/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2215/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2216/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2217/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2218/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2219/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2220/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2221/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2222/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2223/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2224/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2225/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2226/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2227/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2228/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2229/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2230/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2231/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2232/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2233/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2234/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2235/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2236/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2237/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2238/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2239/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2240/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2241/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2242/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2243/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2244/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2245/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2246/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2247/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2248/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2249/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2250/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2251/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2252/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2253/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2254/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2255/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2256/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2257/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2258/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2259/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2260/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2261/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2262/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2263/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2264/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2265/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2266/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2267/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2268/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2269/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2270/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2271/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2272/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2273/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2274/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2275/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2276/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2277/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2278/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2279/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2280/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2281/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2282/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2283/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2284/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2285/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2286/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2287/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2288/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2289/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2290/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2291/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2292/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2293/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2294/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2295/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2296/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2297/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2298/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2299/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2300/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /output/camera/mapped\n", + " Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2301/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2302/6895:\n", + "Publish Instance: /output/telemetry/radio\n", + "Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /telemetry/data\n", + " Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2303/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2304/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2305/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2306/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2307/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2308/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2309/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2310/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2311/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2312/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2313/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2314/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2315/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2316/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2317/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2318/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2319/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2320/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2321/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2322/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2323/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2324/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2325/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2326/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2327/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2328/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2329/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2330/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2331/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2332/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2333/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2334/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2335/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2336/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2337/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2338/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2339/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2340/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2341/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2342/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2343/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2344/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2345/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2346/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2347/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2348/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2349/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2350/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2351/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2352/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2353/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2354/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2355/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2356/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2357/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2358/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2359/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2360/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2361/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2362/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2363/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2364/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2365/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2366/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2367/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2368/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2369/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2370/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2371/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2372/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2373/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2374/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2375/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2376/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2377/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2378/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2379/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2380/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2381/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2382/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2383/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2384/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2385/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2386/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2387/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2388/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2389/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2390/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2391/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2392/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2393/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2394/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2395/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2396/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2397/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2398/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2399/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2400/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2401/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2402/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2403/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2404/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2405/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2406/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2407/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2408/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2409/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2410/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2411/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2412/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2413/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2414/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2415/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2416/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2417/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2418/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2419/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2420/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2421/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2422/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2423/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2424/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2425/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2426/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2427/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2428/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2429/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2430/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2431/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2432/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2433/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2434/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2435/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2436/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2437/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2438/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2439/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2440/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2441/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2442/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2443/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2444/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2445/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2446/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2447/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2448/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2449/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2450/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2451/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2452/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2453/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2454/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2455/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2456/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2457/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2458/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2459/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2460/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2461/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2462/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2463/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2464/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2465/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2466/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2467/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2468/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2469/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2470/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2471/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2472/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2473/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2474/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2475/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2476/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2477/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2478/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2479/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2480/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2481/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2482/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2483/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2484/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2485/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2486/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2487/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2488/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2489/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2490/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2491/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2492/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2493/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2494/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2495/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2496/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2497/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2498/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2499/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2500/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2501/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2502/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2503/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2504/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2505/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2506/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2507/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2508/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2509/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2510/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2511/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2512/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2513/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2514/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2515/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2516/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2517/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2518/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2519/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2520/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2521/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2522/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2523/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2524/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2525/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2526/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2527/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2528/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2529/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2530/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2531/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2532/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2533/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2534/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2535/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2536/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2537/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2538/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2539/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2540/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2541/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2542/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2543/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2544/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2545/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2546/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2547/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2548/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2549/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2550/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2551/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2552/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2553/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2554/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2555/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2556/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2557/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2558/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2559/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2560/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2561/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2562/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2563/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2564/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2565/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2566/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2567/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2568/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2569/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2570/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2571/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2572/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2573/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2574/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2575/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2576/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2577/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2578/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2579/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2580/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2581/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2582/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2583/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2584/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2585/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2586/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2587/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2588/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2589/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2590/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2591/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2592/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2593/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2594/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2595/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2596/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2597/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2598/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2599/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2600/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2601/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2602/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2603/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2604/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2605/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2606/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2607/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2608/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2609/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2610/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2611/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2612/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2613/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2614/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2615/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2616/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2617/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2618/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2619/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2620/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2621/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2622/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2623/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2624/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2625/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2626/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2627/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2628/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2629/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2630/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2631/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2632/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2633/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2634/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2635/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2636/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2637/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2638/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2639/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2640/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2641/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2642/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2643/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2644/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2645/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2646/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2647/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2648/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2649/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2650/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2651/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2652/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2653/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2654/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2655/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2656/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2657/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2658/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2659/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2660/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2661/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2662/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2663/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2664/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2665/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2666/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2667/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2668/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2669/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2670/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2671/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2672/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2673/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2674/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2675/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2676/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2677/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2678/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2679/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2680/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2681/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2682/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2683/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2684/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2685/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2686/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2687/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2688/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2689/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2690/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2691/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2692/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2693/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2694/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2695/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2696/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2697/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2698/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2699/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2700/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2701/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2702/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2703/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2704/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2705/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2706/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2707/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2708/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2709/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2710/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2711/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2712/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2713/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2714/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2715/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2716/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2717/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2718/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2719/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2720/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2721/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2722/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2723/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2724/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2725/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2726/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2727/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2728/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2729/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2730/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2731/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2732/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2733/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2734/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2735/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2736/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2737/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2738/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2739/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2740/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2741/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2742/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2743/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2744/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2745/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2746/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2747/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2748/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2749/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2750/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2751/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2752/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2753/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2754/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2755/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2756/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2757/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2758/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2759/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2760/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2761/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2762/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2763/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2764/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2765/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2766/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2767/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2768/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2769/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2770/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2771/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2772/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2773/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2774/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2775/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2776/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2777/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2778/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2779/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2780/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2781/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2782/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2783/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2784/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2785/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2786/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2787/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2788/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2789/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2790/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2791/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2792/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2793/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2794/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2795/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2796/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2797/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2798/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2799/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2800/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2801/6895:\n", + "Publish Instance: /output/camera/mapped\n", + "Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/geometric\n", + " Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2802/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2803/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2804/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2805/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2806/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2807/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2808/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2809/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2810/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2811/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2812/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2813/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2814/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2815/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2816/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2817/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2818/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2819/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2820/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2821/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2822/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2823/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2824/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2825/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2826/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2827/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2828/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2829/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2830/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2831/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2832/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2833/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2834/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2835/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2836/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2837/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2838/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2839/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2840/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2841/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2842/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2843/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2844/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2845/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2846/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2847/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2848/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2849/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2850/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2851/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2852/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2853/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2854/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2855/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2856/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2857/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2858/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2859/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2860/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2861/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2862/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2863/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2864/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2865/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2866/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2867/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2868/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2869/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2870/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2871/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2872/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2873/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2874/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2875/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2876/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2877/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2878/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2879/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2880/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2881/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2882/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2883/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2884/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2885/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2886/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2887/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2888/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2889/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2890/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2891/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2892/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2893/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2894/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2895/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2896/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2897/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2898/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2899/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2900/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2901/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2902/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2903/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2904/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2905/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2906/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2907/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2908/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2909/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2910/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2911/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2912/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2913/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2914/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2915/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2916/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2917/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2918/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2919/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2920/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2921/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2922/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2923/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2924/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2925/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2926/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2927/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2928/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2929/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2930/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2931/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2932/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2933/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2934/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2935/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2936/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2937/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2938/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2939/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2940/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2941/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2942/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2943/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2944/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2945/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2946/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2947/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2948/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2949/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2950/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2951/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2952/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2953/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2954/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2955/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2956/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2957/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2958/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2959/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2960/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2961/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2962/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2963/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2964/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2965/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2966/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2967/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2968/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2969/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2970/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2971/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2972/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2973/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2974/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2975/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2976/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2977/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2978/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2979/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2980/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2981/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2982/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2983/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2984/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2985/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2986/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2987/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2988/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2989/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2990/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2991/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2992/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2993/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2994/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2995/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2996/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2997/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2998/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 2999/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3000/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3001/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3002/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3003/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3004/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3005/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3006/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3007/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3008/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3009/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3010/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3011/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3012/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3013/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3014/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3015/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3016/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3017/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3018/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3019/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3020/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3021/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3022/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3023/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3024/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3025/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3026/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3027/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3028/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3029/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3030/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3031/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3032/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3033/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3034/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3035/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3036/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3037/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3038/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3039/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3040/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3041/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3042/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3043/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3044/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3045/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3046/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3047/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3048/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3049/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3050/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3051/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3052/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3053/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3054/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3055/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3056/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3057/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3058/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3059/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3060/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3061/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3062/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3063/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3064/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3065/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3066/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3067/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3068/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3069/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3070/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3071/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3072/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3073/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3074/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3075/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3076/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3077/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3078/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3079/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3080/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3081/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3082/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3083/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3084/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3085/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3086/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3087/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3088/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3089/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3090/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3091/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3092/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3093/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3094/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3095/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3096/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3097/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3098/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3099/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3100/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3101/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3102/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3103/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3104/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3105/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3106/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3107/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3108/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3109/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3110/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3111/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3112/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3113/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3114/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3115/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3116/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3117/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3118/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3119/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3120/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3121/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3122/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3123/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3124/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3125/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3126/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3127/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3128/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3129/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3130/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3131/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3132/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3133/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3134/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3135/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3136/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3137/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3138/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3139/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3140/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3141/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3142/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3143/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3144/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3145/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3146/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3147/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3148/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3149/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3150/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3151/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3152/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3153/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3154/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3155/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3156/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3157/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3158/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3159/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3160/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3161/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3162/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3163/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3164/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3165/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3166/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3167/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3168/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3169/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3170/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3171/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3172/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3173/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3174/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3175/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3176/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3177/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3178/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3179/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3180/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3181/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3182/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3183/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3184/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3185/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3186/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3187/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3188/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3189/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3190/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3191/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3192/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3193/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3194/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3195/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3196/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3197/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3198/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3199/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3200/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3201/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3202/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3203/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3204/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3205/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3206/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3207/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3208/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3209/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3210/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3211/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3212/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3213/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3214/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3215/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3216/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3217/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3218/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3219/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3220/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3221/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3222/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3223/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3224/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3225/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3226/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3227/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3228/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3229/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3230/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3231/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3232/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3233/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3234/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3235/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3236/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3237/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3238/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3239/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3240/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3241/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3242/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3243/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3244/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3245/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3246/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3247/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3248/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3249/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3250/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3251/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3252/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3253/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3254/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3255/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3256/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3257/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3258/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3259/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3260/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3261/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3262/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3263/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3264/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3265/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3266/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3267/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3268/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3269/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3270/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3271/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3272/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3273/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3274/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3275/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3276/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3277/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3278/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3279/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3280/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3281/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3282/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3283/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3284/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3285/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3286/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3287/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3288/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3289/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3290/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3291/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3292/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3293/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3294/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3295/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3296/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3297/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3298/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3299/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3300/6895:\n", + "Publish Instance: /output/classifier/classification\n", + "Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/radiometric\n", + " Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /camera/debayered\n", + " Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/camera/raw\n", + " Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3301/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3302/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3303/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3304/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3305/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3306/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3307/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3308/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3309/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3310/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3311/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3312/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3313/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3314/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3315/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3316/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3317/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3318/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3319/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3320/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3321/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3322/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3323/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3324/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3325/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3326/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3327/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3328/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3329/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3330/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3331/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3332/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3333/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3334/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3335/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3336/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3337/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3338/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3339/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3340/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3341/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3342/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3343/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3344/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3345/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3346/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3347/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3348/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3349/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3350/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3351/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3352/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3353/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3354/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3355/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3356/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3357/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3358/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3359/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3360/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3361/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3362/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3363/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3364/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3365/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3366/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3367/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3368/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3369/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3370/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3371/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3372/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3373/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3374/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3375/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3376/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3377/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3378/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3379/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3380/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3381/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3382/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3383/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3384/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3385/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3386/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3387/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3388/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3389/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3390/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3391/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3392/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3393/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3394/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3395/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3396/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3397/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3398/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3399/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3400/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3401/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3402/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3403/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3404/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3405/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3406/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3407/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3408/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3409/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3410/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3411/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3412/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3413/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3414/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3415/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3416/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3417/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3418/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3419/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3420/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3421/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3422/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3423/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3424/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3425/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3426/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3427/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3428/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3429/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3430/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3431/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3432/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3433/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3434/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3435/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3436/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3437/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3438/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3439/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3440/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3441/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3442/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3443/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3444/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3445/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3446/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3447/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3448/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3449/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3450/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3451/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3452/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3453/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3454/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3455/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3456/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3457/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3458/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3459/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3460/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3461/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3462/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3463/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3464/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3465/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3466/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3467/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3468/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3469/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3470/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3471/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3472/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3473/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3474/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3475/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3476/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3477/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3478/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3479/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3480/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3481/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3482/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3483/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3484/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3485/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3486/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3487/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3488/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3489/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3490/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3491/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3492/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3493/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3494/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3495/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3496/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3497/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3498/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3499/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3500/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3501/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3502/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3503/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3504/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3505/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3506/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3507/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3508/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3509/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3510/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3511/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3512/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3513/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3514/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3515/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3516/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3517/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3518/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3519/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3520/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3521/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3522/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3523/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3524/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3525/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3526/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3527/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3528/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3529/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3530/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3531/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3532/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3533/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3534/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3535/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3536/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3537/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3538/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3539/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3540/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3541/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3542/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3543/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3544/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3545/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3546/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3547/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3548/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3549/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3550/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3551/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3552/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3553/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3554/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3555/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3556/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3557/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3558/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3559/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3560/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3561/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3562/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3563/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3564/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3565/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3566/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3567/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3568/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3569/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3570/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3571/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3572/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3573/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3574/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3575/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3576/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3577/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3578/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3579/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3580/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3581/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3582/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3583/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3584/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3585/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3586/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3587/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3588/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3589/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3590/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3591/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3592/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3593/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3594/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3595/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3596/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3597/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3598/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3599/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3600/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3601/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3602/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3603/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3604/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3605/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3606/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3607/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3608/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3609/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3610/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3611/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3612/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3613/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3614/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3615/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3616/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3617/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3618/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3619/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3620/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3621/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3622/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3623/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3624/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3625/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3626/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3627/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3628/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3629/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3630/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3631/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3632/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3633/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3634/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3635/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3636/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3637/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3638/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3639/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3640/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3641/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3642/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3643/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3644/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3645/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3646/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3647/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3648/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3649/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3650/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3651/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3652/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3653/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3654/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3655/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3656/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3657/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3658/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3659/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3660/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3661/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3662/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3663/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3664/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3665/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3666/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3667/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3668/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3669/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3670/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3671/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3672/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3673/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3674/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3675/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3676/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3677/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3678/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3679/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3680/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3681/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3682/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3683/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3684/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3685/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3686/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3687/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3688/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3689/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3690/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3691/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3692/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3693/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3694/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3695/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3696/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3697/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3698/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3699/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3700/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3701/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3702/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3703/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3704/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3705/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3706/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3707/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3708/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3709/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3710/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3711/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3712/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3713/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3714/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3715/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3716/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3717/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3718/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3719/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3720/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3721/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3722/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3723/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3724/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3725/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3726/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3727/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3728/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3729/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3730/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3731/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3732/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3733/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3734/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3735/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3736/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3737/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3738/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3739/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3740/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3741/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3742/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3743/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3744/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3745/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3746/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3747/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3748/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3749/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3750/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3751/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3752/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3753/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3754/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3755/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3756/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3757/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3758/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3759/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3760/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3761/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3762/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3763/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3764/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3765/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3766/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3767/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3768/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3769/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3770/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3771/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3772/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3773/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3774/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3775/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3776/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3777/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3778/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3779/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3780/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3781/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3782/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3783/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3784/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3785/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3786/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3787/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3788/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3789/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3790/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3791/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3792/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3793/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3794/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3795/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3796/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3797/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3798/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3799/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3800/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3801/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3802/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3803/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3804/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3805/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3806/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3807/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3808/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3809/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3810/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3811/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3812/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3813/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3814/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3815/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3816/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3817/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3818/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3819/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3820/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3821/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3822/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3823/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3824/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3825/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3826/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3827/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3828/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3829/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3830/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3831/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3832/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3833/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3834/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3835/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3836/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3837/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3838/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3839/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3840/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3841/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3842/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3843/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3844/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3845/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3846/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3847/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3848/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3849/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3850/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3851/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3852/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3853/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3854/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3855/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3856/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3857/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3858/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3859/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3860/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3861/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3862/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3863/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3864/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3865/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3866/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3867/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3868/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3869/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3870/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3871/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3872/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3873/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3874/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3875/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3876/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3877/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3878/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3879/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3880/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3881/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3882/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3883/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3884/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3885/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3886/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3887/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3888/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3889/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3890/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3891/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3892/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3893/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3894/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3895/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3896/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3897/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3898/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3899/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3900/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3901/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3902/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3903/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3904/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3905/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3906/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3907/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3908/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3909/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3910/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3911/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3912/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3913/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3914/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3915/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3916/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3917/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3918/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3919/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3920/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3921/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3922/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3923/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3924/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3925/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3926/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3927/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3928/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3929/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3930/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3931/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3932/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3933/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3934/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3935/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3936/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3937/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3938/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3939/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3940/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3941/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3942/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3943/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3944/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3945/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3946/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3947/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3948/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3949/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3950/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3951/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3952/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3953/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3954/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3955/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3956/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3957/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3958/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3959/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3960/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3961/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3962/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3963/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3964/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3965/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3966/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3967/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3968/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3969/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3970/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3971/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3972/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3973/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3974/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3975/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3976/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3977/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3978/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3979/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3980/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3981/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3982/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3983/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3984/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3985/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3986/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3987/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3988/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3989/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3990/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3991/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3992/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3993/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3994/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3995/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3996/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3997/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3998/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 3999/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4000/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4001/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4002/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4003/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4004/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4005/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4006/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4007/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4008/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4009/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4010/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4011/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4012/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4013/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4014/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4015/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4016/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4017/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4018/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4019/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4020/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4021/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4022/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4023/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4024/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4025/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4026/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4027/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4028/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4029/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4030/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4031/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4032/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4033/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4034/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4035/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4036/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4037/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4038/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4039/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4040/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4041/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4042/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4043/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4044/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4045/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4046/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4047/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4048/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4049/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4050/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4051/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4052/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4053/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4054/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4055/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4056/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4057/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4058/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4059/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4060/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4061/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4062/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4063/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4064/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4065/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4066/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4067/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4068/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4069/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4070/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4071/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4072/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4073/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4074/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4075/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4076/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4077/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4078/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4079/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4080/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4081/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4082/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4083/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4084/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4085/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4086/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4087/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4088/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4089/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4090/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4091/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4092/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4093/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4094/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4095/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4096/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4097/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4098/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4099/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4100/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4101/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4102/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4103/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4104/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4105/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4106/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4107/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4108/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4109/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4110/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4111/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4112/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4113/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4114/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4115/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4116/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4117/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4118/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4119/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4120/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4121/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4122/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4123/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4124/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4125/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4126/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4127/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4128/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4129/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4130/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4131/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4132/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4133/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4134/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4135/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4136/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4137/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4138/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4139/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4140/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4141/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4142/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4143/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4144/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4145/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4146/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4147/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4148/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4149/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4150/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4151/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4152/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4153/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4154/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4155/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4156/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4157/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4158/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4159/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4160/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4161/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4162/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4163/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4164/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4165/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4166/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4167/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4168/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4169/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4170/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4171/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4172/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4173/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4174/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4175/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4176/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4177/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4178/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4179/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4180/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4181/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4182/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4183/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4184/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4185/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4186/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4187/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4188/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4189/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4190/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4191/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4192/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4193/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4194/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4195/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4196/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4197/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4198/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4199/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4200/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4201/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4202/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4203/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4204/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4205/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4206/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4207/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4208/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4209/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4210/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4211/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4212/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4213/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4214/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4215/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4216/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4217/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4218/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4219/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4220/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4221/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4222/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4223/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4224/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4225/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4226/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4227/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4228/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4229/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4230/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4231/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4232/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4233/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4234/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4235/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4236/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4237/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4238/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4239/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4240/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4241/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4242/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4243/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4244/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4245/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4246/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4247/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4248/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4249/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4250/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4251/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4252/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4253/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4254/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4255/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4256/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4257/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4258/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4259/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4260/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4261/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4262/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4263/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4264/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4265/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4266/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4267/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4268/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4269/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4270/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4271/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4272/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4273/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4274/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4275/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4276/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4277/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4278/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4279/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4280/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4281/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4282/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4283/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4284/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4285/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4286/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4287/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4288/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4289/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4290/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4291/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4292/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4293/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4294/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4295/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4296/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4297/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4298/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4299/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4300/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4301/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4302/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4303/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4304/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4305/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4306/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4307/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4308/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4309/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4310/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4311/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4312/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4313/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4314/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4315/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4316/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4317/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4318/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4319/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4320/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4321/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4322/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4323/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4324/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4325/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4326/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4327/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4328/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4329/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4330/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4331/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4332/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4333/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4334/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4335/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4336/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4337/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4338/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4339/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4340/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4341/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4342/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4343/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4344/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4345/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4346/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4347/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4348/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4349/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4350/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4351/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4352/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4353/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4354/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4355/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4356/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4357/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4358/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4359/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4360/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4361/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4362/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4363/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4364/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4365/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4366/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4367/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4368/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4369/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4370/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4371/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4372/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4373/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4374/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4375/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4376/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4377/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4378/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4379/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4380/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4381/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4382/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4383/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4384/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4385/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4386/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4387/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4388/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4389/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4390/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4391/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4392/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4393/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4394/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4395/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4396/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4397/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4398/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4399/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4400/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4401/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4402/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4403/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4404/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4405/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4406/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4407/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4408/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4409/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4410/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4411/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4412/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4413/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4414/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4415/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4416/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4417/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4418/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4419/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4420/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4421/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4422/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4423/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4424/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4425/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4426/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4427/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4428/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4429/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4430/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4431/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4432/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4433/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4434/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4435/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4436/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4437/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4438/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4439/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4440/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4441/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4442/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4443/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4444/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4445/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4446/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4447/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4448/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4449/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4450/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4451/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4452/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4453/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4454/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4455/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4456/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4457/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4458/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4459/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4460/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4461/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4462/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4463/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4464/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4465/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4466/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4467/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4468/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4469/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4470/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4471/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4472/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4473/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4474/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4475/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4476/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4477/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4478/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4479/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4480/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4481/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4482/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4483/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4484/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4485/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4486/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4487/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4488/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4489/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4490/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4491/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4492/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4493/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4494/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4495/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4496/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4497/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4498/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4499/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4500/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4501/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4502/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4503/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4504/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4505/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4506/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4507/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4508/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4509/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4510/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4511/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4512/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4513/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4514/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4515/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4516/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4517/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4518/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4519/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4520/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4521/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4522/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4523/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4524/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4525/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4526/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4527/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4528/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4529/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4530/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4531/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4532/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4533/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4534/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4535/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4536/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4537/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4538/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4539/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4540/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4541/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4542/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4543/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4544/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4545/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4546/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4547/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4548/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4549/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4550/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4551/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4552/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4553/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4554/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4555/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4556/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4557/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4558/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4559/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4560/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4561/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4562/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4563/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4564/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4565/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4566/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4567/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4568/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4569/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4570/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4571/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4572/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4573/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4574/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4575/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4576/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4577/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4578/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4579/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4580/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4581/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4582/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4583/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4584/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4585/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4586/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4587/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4588/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4589/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4590/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4591/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4592/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4593/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4594/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4595/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4596/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4597/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4598/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4599/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4600/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4601/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4602/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4603/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4604/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4605/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4606/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4607/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4608/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4609/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4610/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4611/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4612/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4613/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4614/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4615/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4616/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4617/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4618/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4619/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4620/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4621/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4622/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4623/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4624/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4625/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4626/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4627/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4628/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4629/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4630/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4631/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4632/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4633/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4634/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4635/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4636/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4637/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4638/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4639/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4640/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4641/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4642/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4643/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4644/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4645/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4646/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4647/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4648/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4649/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4650/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4651/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4652/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4653/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4654/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4655/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4656/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4657/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4658/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4659/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4660/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4661/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4662/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4663/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4664/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4665/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4666/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4667/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4668/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4669/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4670/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4671/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4672/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4673/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4674/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4675/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4676/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4677/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4678/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4679/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4680/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4681/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4682/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4683/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4684/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4685/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4686/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4687/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4688/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4689/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4690/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4691/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4692/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4693/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4694/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4695/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4696/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4697/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4698/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4699/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4700/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4701/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4702/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4703/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4704/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4705/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4706/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4707/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4708/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4709/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4710/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4711/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4712/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4713/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4714/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4715/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4716/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4717/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4718/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4719/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4720/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4721/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4722/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4723/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4724/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4725/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4726/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4727/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4728/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4729/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4730/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4731/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4732/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4733/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4734/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4735/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4736/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4737/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4738/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4739/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4740/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4741/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4742/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4743/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4744/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4745/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4746/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4747/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4748/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4749/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4750/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4751/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4752/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4753/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4754/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4755/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4756/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4757/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4758/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4759/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4760/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4761/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4762/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4763/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4764/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4765/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4766/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4767/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4768/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4769/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4770/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4771/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4772/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4773/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4774/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4775/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4776/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4777/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4778/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4779/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4780/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4781/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4782/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4783/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4784/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4785/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4786/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4787/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4788/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4789/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4790/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4791/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4792/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4793/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4794/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4795/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4796/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4797/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4798/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4799/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4800/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4801/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4802/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4803/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4804/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4805/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4806/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4807/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4808/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4809/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4810/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4811/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4812/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4813/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4814/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4815/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4816/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4817/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4818/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4819/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4820/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4821/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4822/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4823/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4824/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4825/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4826/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4827/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4828/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4829/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4830/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4831/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4832/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4833/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4834/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4835/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4836/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4837/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4838/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4839/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4840/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4841/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4842/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4843/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4844/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4845/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4846/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4847/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4848/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4849/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4850/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4851/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4852/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4853/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4854/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4855/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4856/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4857/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4858/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4859/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4860/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4861/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4862/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4863/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4864/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4865/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4866/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4867/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4868/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4869/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4870/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4871/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4872/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4873/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4874/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4875/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4876/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4877/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4878/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4879/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4880/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4881/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4882/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4883/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4884/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4885/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4886/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4887/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4888/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4889/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4890/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4891/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4892/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4893/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4894/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4895/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4896/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4897/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4898/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4899/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4900/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4901/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4902/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4903/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4904/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4905/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4906/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4907/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4908/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4909/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4910/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4911/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4912/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4913/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4914/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4915/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4916/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4917/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4918/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4919/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4920/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4921/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4922/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4923/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4924/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4925/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4926/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4927/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4928/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4929/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4930/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4931/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4932/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4933/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4934/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4935/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4936/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4937/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4938/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4939/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4940/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4941/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4942/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4943/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4944/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4945/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4946/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4947/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4948/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4949/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4950/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4951/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4952/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4953/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4954/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4955/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4956/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4957/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4958/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4959/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4960/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4961/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4962/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4963/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4964/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4965/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4966/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4967/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4968/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4969/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4970/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4971/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4972/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4973/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4974/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4975/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4976/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4977/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4978/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4979/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4980/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4981/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4982/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4983/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4984/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4985/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4986/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4987/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4988/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4989/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4990/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4991/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4992/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4993/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4994/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4995/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4996/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4997/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4998/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 4999/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5000/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5001/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5002/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5003/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5004/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5005/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5006/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5007/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5008/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5009/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5010/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5011/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5012/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5013/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5014/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5015/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5016/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5017/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5018/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5019/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5020/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5021/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5022/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5023/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5024/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5025/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5026/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5027/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5028/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5029/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5030/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5031/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5032/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5033/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5034/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5035/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5036/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5037/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5038/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5039/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5040/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5041/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5042/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5043/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5044/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5045/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5046/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5047/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5048/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5049/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5050/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5051/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5052/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5053/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5054/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5055/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5056/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5057/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5058/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5059/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5060/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5061/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5062/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5063/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5064/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5065/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5066/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5067/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5068/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5069/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5070/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5071/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5072/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5073/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5074/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5075/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5076/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5077/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5078/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5079/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5080/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5081/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5082/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5083/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5084/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5085/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5086/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5087/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5088/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5089/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5090/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5091/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5092/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5093/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5094/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5095/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5096/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5097/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5098/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5099/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5100/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5101/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5102/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5103/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5104/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5105/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5106/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5107/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5108/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5109/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5110/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5111/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5112/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5113/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5114/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5115/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5116/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5117/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5118/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5119/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5120/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5121/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5122/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5123/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5124/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5125/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5126/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5127/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5128/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5129/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5130/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5131/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5132/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5133/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5134/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5135/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5136/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5137/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5138/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5139/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5140/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5141/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5142/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5143/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5144/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5145/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5146/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5147/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5148/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5149/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5150/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5151/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5152/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5153/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5154/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5155/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5156/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5157/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5158/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5159/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5160/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5161/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5162/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5163/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5164/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5165/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5166/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5167/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5168/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5169/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5170/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5171/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5172/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5173/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5174/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5175/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5176/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5177/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5178/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5179/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5180/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5181/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5182/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5183/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5184/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5185/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5186/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5187/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5188/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5189/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5190/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5191/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5192/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5193/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5194/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5195/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5196/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5197/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5198/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5199/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5200/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5201/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5202/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5203/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5204/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5205/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5206/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5207/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5208/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5209/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5210/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5211/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5212/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5213/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5214/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5215/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5216/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5217/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5218/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5219/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5220/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5221/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5222/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5223/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5224/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5225/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5226/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5227/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5228/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5229/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5230/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5231/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5232/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5233/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5234/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5235/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5236/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5237/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5238/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5239/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5240/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5241/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5242/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5243/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5244/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5245/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5246/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5247/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5248/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5249/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5250/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5251/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5252/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5253/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5254/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5255/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5256/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5257/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5258/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5259/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5260/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5261/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5262/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5263/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5264/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5265/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5266/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5267/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5268/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5269/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5270/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5271/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5272/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5273/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5274/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5275/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5276/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5277/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5278/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5279/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5280/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5281/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5282/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5283/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5284/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5285/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5286/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5287/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5288/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5289/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5290/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5291/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5292/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5293/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5294/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5295/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5296/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5297/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5298/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5299/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5300/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5301/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5302/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5303/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5304/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5305/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5306/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5307/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5308/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5309/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5310/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5311/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5312/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5313/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5314/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5315/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5316/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5317/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5318/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5319/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5320/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5321/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5322/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5323/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5324/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5325/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5326/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5327/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5328/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5329/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5330/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5331/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5332/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5333/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5334/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5335/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5336/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5337/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5338/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5339/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5340/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5341/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5342/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5343/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5344/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5345/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5346/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5347/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5348/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5349/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5350/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5351/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5352/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5353/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5354/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5355/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5356/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5357/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5358/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5359/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5360/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5361/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5362/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5363/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5364/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5365/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5366/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5367/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5368/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5369/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5370/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5371/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5372/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5373/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5374/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5375/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5376/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5377/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5378/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5379/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5380/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5381/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5382/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5383/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5384/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5385/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5386/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5387/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5388/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5389/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5390/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5391/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5392/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5393/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5394/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5395/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5396/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5397/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5398/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5399/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5400/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5401/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5402/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5403/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5404/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5405/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5406/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5407/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5408/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5409/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5410/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5411/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5412/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5413/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5414/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5415/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5416/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5417/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5418/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5419/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5420/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5421/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5422/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5423/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5424/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5425/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5426/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5427/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5428/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5429/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5430/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5431/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5432/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5433/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5434/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5435/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5436/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5437/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5438/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5439/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5440/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5441/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5442/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5443/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5444/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5445/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5446/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5447/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5448/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5449/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5450/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5451/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5452/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5453/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5454/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5455/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5456/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5457/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5458/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5459/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5460/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5461/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5462/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5463/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5464/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5465/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5466/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5467/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5468/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5469/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5470/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5471/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5472/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5473/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5474/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5475/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5476/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5477/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5478/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5479/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5480/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5481/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5482/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5483/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5484/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5485/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5486/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5487/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5488/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5489/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5490/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5491/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5492/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5493/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5494/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5495/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5496/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5497/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5498/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5499/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5500/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5501/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5502/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5503/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5504/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5505/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5506/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5507/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5508/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5509/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5510/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5511/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5512/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5513/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5514/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5515/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5516/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5517/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5518/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5519/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5520/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5521/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5522/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5523/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5524/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5525/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5526/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5527/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5528/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5529/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5530/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5531/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5532/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5533/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5534/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5535/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5536/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5537/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5538/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5539/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5540/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5541/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5542/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5543/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5544/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5545/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5546/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5547/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5548/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5549/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5550/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5551/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5552/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5553/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5554/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5555/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5556/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5557/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5558/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5559/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5560/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5561/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5562/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5563/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5564/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5565/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5566/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5567/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5568/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5569/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5570/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5571/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5572/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5573/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5574/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5575/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5576/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5577/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5578/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5579/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5580/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5581/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5582/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5583/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5584/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5585/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5586/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5587/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5588/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5589/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5590/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5591/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5592/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5593/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5594/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5595/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5596/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5597/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5598/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5599/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5600/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5601/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5602/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5603/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5604/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5605/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5606/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5607/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5608/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5609/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5610/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5611/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5612/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5613/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5614/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5615/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5616/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5617/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5618/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5619/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5620/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5621/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5622/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5623/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5624/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5625/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5626/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5627/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5628/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5629/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5630/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5631/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5632/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5633/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5634/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5635/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5636/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5637/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5638/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5639/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5640/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5641/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5642/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5643/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5644/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5645/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5646/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5647/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5648/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5649/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5650/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5651/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5652/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5653/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5654/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5655/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5656/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5657/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5658/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5659/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5660/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5661/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5662/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5663/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5664/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5665/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5666/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5667/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5668/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5669/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5670/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5671/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5672/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5673/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5674/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5675/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5676/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5677/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5678/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5679/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5680/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5681/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5682/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5683/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5684/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5685/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5686/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5687/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5688/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5689/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5690/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5691/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5692/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5693/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5694/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5695/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5696/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5697/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5698/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5699/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5700/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5701/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5702/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5703/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5704/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5705/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5706/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5707/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5708/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5709/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5710/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5711/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5712/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5713/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5714/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5715/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5716/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5717/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5718/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5719/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5720/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5721/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5722/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5723/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5724/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5725/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5726/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5727/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5728/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5729/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5730/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5731/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5732/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5733/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5734/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5735/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5736/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5737/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5738/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5739/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5740/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5741/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5742/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5743/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5744/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5745/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5746/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5747/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5748/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5749/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5750/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5751/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5752/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5753/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5754/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5755/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5756/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5757/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5758/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5759/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5760/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5761/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5762/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5763/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5764/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5765/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5766/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5767/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5768/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5769/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5770/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5771/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5772/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5773/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5774/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5775/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5776/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5777/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5778/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5779/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5780/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5781/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5782/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5783/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5784/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5785/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5786/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5787/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5788/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5789/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5790/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5791/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5792/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5793/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5794/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5795/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5796/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5797/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5798/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5799/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5800/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5801/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5802/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5803/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5804/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5805/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5806/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5807/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5808/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5809/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5810/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5811/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5812/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5813/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5814/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5815/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5816/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5817/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5818/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5819/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5820/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5821/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5822/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5823/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5824/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5825/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5826/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5827/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5828/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5829/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5830/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5831/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5832/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5833/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5834/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5835/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5836/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5837/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5838/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5839/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5840/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5841/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5842/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5843/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5844/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5845/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5846/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5847/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5848/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5849/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5850/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5851/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5852/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5853/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5854/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5855/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5856/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5857/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5858/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5859/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5860/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5861/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5862/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5863/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5864/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5865/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5866/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5867/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5868/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5869/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5870/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5871/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5872/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5873/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5874/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5875/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5876/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5877/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5878/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5879/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5880/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5881/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5882/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5883/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5884/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5885/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5886/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5887/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5888/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5889/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5890/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5891/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5892/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5893/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5894/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5895/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5896/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5897/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5898/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5899/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5900/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5901/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5902/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5903/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5904/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5905/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5906/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5907/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5908/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5909/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5910/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5911/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5912/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5913/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5914/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5915/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5916/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5917/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5918/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5919/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5920/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5921/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5922/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5923/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5924/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5925/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5926/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5927/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5928/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5929/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5930/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5931/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5932/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5933/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5934/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5935/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5936/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5937/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5938/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5939/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5940/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5941/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5942/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5943/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5944/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5945/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5946/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5947/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5948/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5949/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5950/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5951/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5952/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5953/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5954/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5955/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5956/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5957/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5958/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5959/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5960/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5961/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5962/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5963/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5964/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5965/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5966/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5967/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5968/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5969/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5970/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5971/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5972/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5973/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5974/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5975/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5976/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5977/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5978/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5979/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5980/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5981/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5982/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5983/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5984/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5985/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5986/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5987/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5988/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5989/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5990/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5991/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5992/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5993/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5994/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5995/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5996/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5997/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5998/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 5999/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6000/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6001/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6002/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6003/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6004/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6005/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6006/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6007/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6008/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6009/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6010/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6011/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6012/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6013/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6014/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6015/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6016/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6017/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6018/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6019/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6020/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6021/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6022/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6023/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6024/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6025/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6026/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6027/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6028/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6029/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6030/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6031/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6032/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6033/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6034/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6035/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6036/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6037/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6038/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6039/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6040/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6041/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6042/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6043/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6044/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6045/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6046/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6047/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6048/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6049/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6050/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6051/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6052/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6053/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6054/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6055/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6056/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6057/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6058/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6059/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6060/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6061/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6062/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6063/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6064/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6065/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6066/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6067/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6068/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6069/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6070/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6071/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6072/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6073/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6074/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6075/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6076/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6077/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6078/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6079/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6080/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6081/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6082/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6083/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6084/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6085/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6086/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6087/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6088/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6089/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6090/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6091/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6092/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6093/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6094/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6095/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6096/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6097/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6098/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6099/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6100/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6101/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6102/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6103/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6104/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6105/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6106/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6107/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6108/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6109/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6110/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6111/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6112/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6113/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6114/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6115/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6116/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6117/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6118/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6119/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6120/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6121/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6122/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6123/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6124/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6125/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6126/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6127/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6128/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6129/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6130/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6131/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6132/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6133/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6134/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6135/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6136/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6137/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6138/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6139/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6140/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6141/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6142/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6143/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6144/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6145/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6146/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6147/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6148/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6149/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6150/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6151/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6152/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6153/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6154/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6155/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6156/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6157/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6158/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6159/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6160/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6161/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6162/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6163/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6164/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6165/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6166/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6167/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6168/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6169/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6170/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6171/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6172/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6173/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6174/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6175/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6176/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6177/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6178/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6179/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6180/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6181/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6182/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6183/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6184/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6185/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6186/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6187/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6188/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6189/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6190/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6191/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6192/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6193/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6194/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6195/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6196/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6197/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6198/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6199/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6200/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6201/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6202/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6203/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6204/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6205/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6206/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6207/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6208/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6209/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6210/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6211/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6212/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6213/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6214/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6215/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6216/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6217/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6218/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6219/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6220/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6221/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6222/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6223/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6224/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6225/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6226/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6227/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6228/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6229/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6230/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6231/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6232/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6233/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6234/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6235/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6236/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6237/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6238/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6239/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6240/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6241/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6242/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6243/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6244/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6245/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6246/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6247/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6248/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6249/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6250/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6251/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6252/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6253/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6254/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6255/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6256/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6257/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6258/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6259/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6260/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6261/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6262/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6263/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6264/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6265/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6266/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6267/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6268/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6269/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6270/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6271/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6272/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6273/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6274/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6275/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6276/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6277/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6278/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6279/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6280/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6281/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6282/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6283/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6284/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6285/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6286/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6287/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6288/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6289/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6290/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6291/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6292/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6293/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6294/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6295/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6296/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6297/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6298/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6299/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6300/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6301/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6302/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6303/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6304/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6305/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6306/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6307/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6308/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6309/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6310/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6311/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6312/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6313/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6314/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6315/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6316/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6317/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6318/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6319/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6320/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6321/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6322/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6323/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6324/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6325/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6326/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6327/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6328/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6329/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6330/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6331/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6332/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6333/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6334/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6335/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6336/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6337/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6338/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6339/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6340/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6341/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6342/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6343/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6344/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6345/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6346/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6347/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6348/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6349/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6350/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6351/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6352/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6353/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6354/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6355/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6356/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6357/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6358/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6359/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6360/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6361/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6362/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6363/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6364/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6365/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6366/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6367/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6368/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6369/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6370/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6371/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6372/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6373/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6374/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6375/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6376/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6377/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6378/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6379/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6380/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6381/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6382/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6383/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6384/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6385/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6386/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6387/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6388/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6389/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6390/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6391/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6392/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6393/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6394/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6395/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6396/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6397/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6398/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6399/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6400/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6401/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6402/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6403/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6404/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6405/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6406/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6407/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6408/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6409/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6410/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6411/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6412/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6413/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6414/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6415/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6416/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6417/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6418/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6419/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6420/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6421/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6422/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6423/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6424/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6425/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6426/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6427/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6428/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6429/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6430/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6431/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6432/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6433/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6434/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6435/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6436/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6437/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6438/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6439/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6440/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6441/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6442/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6443/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6444/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6445/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6446/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6447/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6448/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6449/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6450/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6451/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6452/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6453/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6454/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6455/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6456/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6457/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6458/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6459/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6460/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6461/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6462/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6463/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6464/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6465/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6466/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6467/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6468/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6469/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6470/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6471/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6472/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6473/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6474/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6475/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6476/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6477/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6478/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6479/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6480/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6481/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6482/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6483/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6484/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6485/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6486/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6487/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6488/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6489/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6490/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6491/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6492/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6493/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6494/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6495/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6496/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6497/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6498/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6499/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6500/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6501/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6502/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6503/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6504/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6505/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6506/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6507/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6508/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6509/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6510/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6511/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6512/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6513/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6514/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6515/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6516/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6517/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6518/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6519/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6520/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6521/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6522/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6523/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6524/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6525/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6526/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6527/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6528/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6529/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6530/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6531/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6532/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6533/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6534/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6535/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6536/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6537/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6538/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6539/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6540/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6541/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6542/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6543/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6544/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6545/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6546/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6547/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6548/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6549/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6550/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6551/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6552/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6553/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6554/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6555/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6556/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6557/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6558/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6559/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6560/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6561/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6562/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6563/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6564/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6565/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6566/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6567/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6568/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6569/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6570/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6571/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6572/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6573/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6574/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6575/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6576/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6577/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6578/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6579/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6580/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6581/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6582/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6583/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6584/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6585/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6586/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6587/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6588/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6589/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6590/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6591/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6592/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6593/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6594/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6595/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6596/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6597/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6598/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6599/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6600/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6601/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6602/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6603/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6604/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6605/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6606/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6607/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6608/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6609/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6610/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6611/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6612/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6613/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6614/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6615/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6616/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6617/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6618/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6619/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6620/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6621/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6622/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6623/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6624/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6625/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6626/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6627/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6628/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6629/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6630/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6631/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6632/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6633/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6634/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6635/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6636/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6637/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6638/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6639/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6640/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6641/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6642/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6643/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6644/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6645/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6646/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6647/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6648/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6649/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6650/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6651/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6652/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6653/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6654/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6655/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6656/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6657/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6658/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6659/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6660/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6661/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6662/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6663/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6664/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6665/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6666/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6667/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6668/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6669/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6670/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6671/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6672/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6673/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6674/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6675/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6676/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6677/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6678/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6679/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6680/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6681/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6682/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6683/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6684/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6685/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6686/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6687/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6688/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6689/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6690/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6691/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6692/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6693/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6694/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6695/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6696/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6697/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6698/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6699/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6700/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6701/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6702/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6703/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6704/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6705/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6706/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6707/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6708/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6709/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6710/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6711/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6712/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6713/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6714/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6715/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6716/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6717/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6718/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6719/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6720/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6721/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6722/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6723/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6724/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6725/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6726/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6727/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6728/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6729/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6730/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6731/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6732/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6733/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6734/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6735/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6736/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6737/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6738/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6739/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6740/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6741/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6742/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6743/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6744/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6745/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6746/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6747/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6748/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6749/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6750/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6751/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6752/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6753/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6754/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6755/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6756/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6757/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6758/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6759/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6760/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6761/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6762/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6763/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6764/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6765/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6766/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6767/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6768/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6769/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6770/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6771/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6772/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6773/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6774/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6775/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6776/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6777/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6778/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6779/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6780/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6781/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6782/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6783/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6784/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6785/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6786/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6787/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6788/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6789/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6790/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6791/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6792/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6793/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6794/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6795/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6796/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6797/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6798/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6799/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6800/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6801/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6802/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6803/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6804/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6805/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6806/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6807/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6808/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6809/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6810/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6811/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6812/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6813/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6814/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6815/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6816/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6817/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6818/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6819/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6820/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6821/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6822/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6823/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6824/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6825/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6826/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6827/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6828/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6829/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6830/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6831/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6832/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6833/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6834/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6835/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6836/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6837/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6838/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6839/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6840/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6841/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6842/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6843/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6844/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6845/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6846/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6847/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6848/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6849/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6850/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6851/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6852/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6853/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6854/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6855/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6856/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6857/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6858/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6859/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6860/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6861/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6862/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6863/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6864/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6865/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6866/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6867/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6868/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6869/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6870/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6871/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6872/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6873/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6874/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6875/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6876/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6877/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6878/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6879/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6880/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6881/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6882/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6883/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6884/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6885/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6886/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6887/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6888/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6889/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/imu/data\n", + " Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6890/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6891/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6892/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/operator/commands\n", + " Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6893/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/gps/fix\n", + " Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6894/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/lidar/scan\n", + " Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "Tree 6895/6895:\n", + "Publish Instance: /output/flight/cmd\n", + "Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /flight/plan\n", + " Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /sensors/fused\n", + " Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " Publish Instance: /input/baro/alt\n", + " Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + " Callback Instance: std::_Bind))(std::shared_ptr > >)>\n", + "\n", + "End of Dependency Trees\n", + "\n", + "Published topics seen so far: 0:, \n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Extracting E2E paths: 100%|██████████| 6895/6895 [00:00<00:00, 39043.30it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Path 1/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 3/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 4/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 5/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 6/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 7/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 8/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 9/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 10/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 11/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 12/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 13/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 14/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 15/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 16/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 17/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 18/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 19/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 20/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 21/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 22/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 23/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 24/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 25/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 26/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 27/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 28/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 29/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 30/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 31/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 32/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 33/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 34/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 35/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 36/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 37/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 38/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 39/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 40/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 41/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 42/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 43/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 44/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 45/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 46/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 47/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 48/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 49/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 50/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 51/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 52/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 53/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 54/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 55/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 56/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 57/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 58/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 59/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 60/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 61/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 62/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 63/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 64/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 65/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 66/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 67/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 68/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 69/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 70/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 71/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 72/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 73/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 74/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 75/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 76/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 77/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 78/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 79/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 80/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 81/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 82/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 83/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 84/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 85/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 86/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 87/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 88/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 89/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 90/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 91/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 92/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 93/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 94/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 95/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 96/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 97/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 98/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 99/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 100/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 101/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 102/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 103/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 104/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 105/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 106/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 107/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 108/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 109/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 110/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 111/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 112/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 113/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 114/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 115/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 116/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 117/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 118/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 119/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 120/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 121/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 122/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 123/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 124/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 125/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 126/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 127/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 128/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 129/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 130/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 131/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 132/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 133/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 134/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 135/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 136/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 137/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 138/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 139/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 140/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 141/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 142/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 143/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 144/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 145/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 146/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 147/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 148/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 149/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 150/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 151/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 152/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 153/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 154/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 155/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 156/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 157/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 158/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 159/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 160/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 161/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 162/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 163/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 164/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 165/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 166/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 167/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 168/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 169/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 170/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 171/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 172/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 173/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 174/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 175/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 176/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 177/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 178/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 179/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 180/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 181/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 182/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 183/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 184/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 185/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 186/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 187/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 188/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 189/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 190/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 191/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 192/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 193/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 194/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 195/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 196/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 197/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 198/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 199/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 200/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 201/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 202/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 203/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 204/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 205/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 206/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 207/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 208/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 209/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 210/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 211/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 212/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 213/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 214/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 215/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 216/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 217/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 218/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 219/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 220/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 221/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 222/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 223/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 224/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 225/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 226/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 227/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 228/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 229/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 230/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 231/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 232/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 233/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 234/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 235/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 236/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 237/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 238/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 239/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 240/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 241/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 242/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 243/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 244/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 245/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 246/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 247/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 248/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 249/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 250/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 251/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 252/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 253/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 254/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 255/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 256/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 257/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 258/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 259/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 260/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 261/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 262/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 263/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 264/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 265/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 266/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 267/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 268/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 269/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 270/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 271/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 272/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 273/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 274/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 275/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 276/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 277/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 278/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 279/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 280/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 281/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 282/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 283/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 284/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 285/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 286/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 287/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 288/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 289/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 290/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 291/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 292/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 293/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 294/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 295/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 296/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 297/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 298/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 299/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 300/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 301/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 302/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 303/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 304/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 305/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 306/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 307/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 308/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 309/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 310/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 311/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 312/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 313/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 314/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 315/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 316/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 317/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 318/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 319/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 320/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 321/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 322/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 323/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 324/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 325/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 326/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 327/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 328/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 329/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 330/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 331/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 332/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 333/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 334/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 335/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 336/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 337/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 338/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 339/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 340/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 341/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 342/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 343/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 344/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 345/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 346/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 347/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 348/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 349/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 350/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 351/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 352/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 353/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 354/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 355/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 356/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 357/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 358/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 359/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 360/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 361/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 362/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 363/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 364/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 365/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 366/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 367/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 368/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 369/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 370/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 371/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 372/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 373/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 374/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 375/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 376/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 377/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 378/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 379/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 380/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 381/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 382/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 383/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 384/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 385/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 386/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 387/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 388/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 389/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 390/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 391/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 392/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 393/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 394/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 395/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 396/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 397/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 398/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 399/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 400/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 401/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 402/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 403/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 404/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 405/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 406/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 407/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 408/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 409/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 410/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 411/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 412/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 413/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 414/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 415/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 416/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 417/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 418/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 419/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 420/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 421/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 422/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 423/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 424/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 425/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 426/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 427/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 428/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 429/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 430/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 431/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 432/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 433/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 434/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 435/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 436/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 437/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 438/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 439/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 440/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 441/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 442/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 443/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 444/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 445/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 446/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 447/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 448/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 449/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 450/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 451/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 452/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 453/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 454/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 455/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 456/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 457/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 458/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 459/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 460/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 461/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 462/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 463/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 464/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 465/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 466/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 467/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 468/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 469/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 470/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 471/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 472/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 473/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 474/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 475/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 476/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 477/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 478/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 479/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 480/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 481/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 482/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 483/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 484/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 485/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 486/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 487/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 488/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 489/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 490/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 491/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 492/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 493/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 494/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 495/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 496/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 497/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 498/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 499/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 500/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 501/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 502/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 503/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 504/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 505/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 506/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 507/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 508/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 509/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 510/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 511/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 512/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 513/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 514/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 515/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 516/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 517/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 518/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 519/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 520/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 521/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 522/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 523/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 524/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 525/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 526/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 527/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 528/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 529/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 530/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 531/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 532/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 533/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 534/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 535/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 536/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 537/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 538/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 539/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 540/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 541/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 542/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 543/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 544/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 545/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 546/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 547/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 548/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 549/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 550/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 551/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 552/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 553/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 554/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 555/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 556/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 557/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 558/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 559/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 560/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 561/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 562/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 563/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 564/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 565/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 566/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 567/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 568/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 569/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 570/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 571/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 572/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 573/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 574/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 575/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 576/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 577/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 578/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 579/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 580/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 581/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 582/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 583/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 584/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 585/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 586/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 587/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 588/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 589/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 590/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 591/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 592/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 593/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 594/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 595/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 596/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 597/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 598/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 599/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 600/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 601/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 602/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 603/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 604/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 605/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 606/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 607/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 608/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 609/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 610/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 611/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 612/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 613/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 614/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 615/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 616/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 617/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 618/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 619/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 620/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 621/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 622/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 623/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 624/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 625/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 626/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 627/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 628/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 629/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 630/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 631/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 632/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 633/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 634/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 635/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 636/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 637/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 638/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 639/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 640/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 641/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 642/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 643/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 644/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 645/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 646/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 647/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 648/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 649/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 650/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 651/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 652/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 653/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 654/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 655/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 656/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 657/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 658/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 659/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 660/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 661/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 662/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 663/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 664/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 665/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 666/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 667/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 668/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 669/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 670/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 671/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 672/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 673/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 674/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 675/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 676/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 677/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 678/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 679/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 680/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 681/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 682/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 683/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 684/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 685/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 686/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 687/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 688/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 689/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 690/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 691/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 692/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 693/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 694/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 695/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 696/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 697/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 698/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 699/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 700/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 701/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 702/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 703/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 704/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 705/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 706/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 707/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 708/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 709/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 710/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 711/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 712/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 713/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 714/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 715/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 716/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 717/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 718/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 719/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 720/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 721/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 722/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 723/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 724/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 725/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 726/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 727/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 728/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 729/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 730/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 731/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 732/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 733/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 734/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 735/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 736/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 737/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 738/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 739/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 740/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 741/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 742/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 743/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 744/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 745/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 746/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 747/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 748/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 749/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 750/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 751/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 752/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 753/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 754/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 755/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 756/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 757/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 758/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 759/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 760/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 761/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 762/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 763/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 764/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 765/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 766/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 767/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 768/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 769/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 770/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 771/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 772/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 773/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 774/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 775/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 776/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 777/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 778/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 779/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 780/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 781/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 782/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 783/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 784/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 785/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 786/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 787/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 788/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 789/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 790/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 791/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 792/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 793/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 794/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 795/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 796/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 797/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 798/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 799/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 800/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 801/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 802/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 803/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 804/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 805/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 806/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 807/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 808/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 809/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 810/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 811/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 812/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 813/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 814/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 815/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 816/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 817/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 818/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 819/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 820/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 821/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 822/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 823/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 824/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 825/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 826/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 827/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 828/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 829/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 830/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 831/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 832/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 833/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 834/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 835/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 836/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 837/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 838/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 839/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 840/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 841/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 842/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 843/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 844/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 845/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 846/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 847/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 848/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 849/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 850/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 851/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 852/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 853/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 854/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 855/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 856/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 857/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 858/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 859/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 860/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 861/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 862/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 863/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 864/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 865/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 866/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 867/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 868/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 869/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 870/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 871/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 872/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 873/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 874/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 875/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 876/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 877/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 878/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 879/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 880/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 881/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 882/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 883/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 884/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 885/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 886/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 887/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 888/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 889/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 890/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 891/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 892/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 893/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 894/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 895/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 896/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 897/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 898/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 899/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 900/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 901/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 902/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 903/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 904/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 905/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 906/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 907/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 908/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 909/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 910/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 911/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 912/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 913/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 914/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 915/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 916/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 917/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 918/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 919/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 920/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 921/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 922/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 923/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 924/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 925/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 926/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 927/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 928/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 929/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 930/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 931/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 932/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 933/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 934/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 935/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 936/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 937/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 938/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 939/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 940/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 941/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 942/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 943/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 944/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 945/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 946/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 947/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 948/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 949/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 950/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 951/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 952/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 953/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 954/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 955/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 956/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 957/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 958/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 959/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 960/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 961/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 962/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 963/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 964/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 965/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 966/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 967/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 968/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 969/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 970/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 971/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 972/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 973/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 974/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 975/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 976/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 977/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 978/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 979/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 980/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 981/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 982/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 983/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 984/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 985/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 986/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 987/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 988/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 989/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 990/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 991/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 992/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 993/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 994/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 995/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 996/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 997/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 998/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 999/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1000/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1001/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1002/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1003/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1004/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1005/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1006/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1007/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1008/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1009/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1010/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1011/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1012/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1013/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1014/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1015/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1016/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1017/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1018/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1019/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1020/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1021/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1022/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1023/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1024/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1025/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1026/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1027/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1028/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1029/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1030/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1031/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1032/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1033/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1034/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1035/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1036/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1037/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1038/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1039/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1040/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1041/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1042/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1043/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1044/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1045/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1046/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1047/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1048/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1049/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1050/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1051/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1052/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1053/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1054/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1055/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1056/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1057/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1058/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1059/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1060/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1061/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1062/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1063/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1064/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1065/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1066/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1067/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1068/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1069/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1070/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1071/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1072/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1073/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1074/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1075/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1076/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1077/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1078/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1079/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1080/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1081/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1082/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1083/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1084/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1085/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1086/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1087/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1088/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1089/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1090/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1091/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1092/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1093/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1094/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1095/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1096/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1097/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1098/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1099/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1100/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1101/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1102/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1103/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1104/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1105/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1106/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1107/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1108/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1109/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1110/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1111/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1112/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1113/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1114/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1115/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1116/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1117/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1118/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1119/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1120/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1121/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1122/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1123/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1124/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1125/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1126/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1127/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1128/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1129/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1130/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1131/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1132/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1133/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1134/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1135/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1136/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1137/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1138/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1139/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1140/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1141/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1142/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1143/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1144/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1145/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1146/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1147/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1148/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1149/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1150/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1151/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1152/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1153/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1154/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1155/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1156/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1157/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1158/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1159/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1160/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1161/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1162/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1163/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1164/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1165/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1166/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1167/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1168/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1169/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1170/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1171/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1172/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1173/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1174/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1175/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1176/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1177/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1178/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1179/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1180/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1181/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1182/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1183/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1184/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1185/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1186/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1187/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1188/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1189/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1190/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1191/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1192/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1193/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1194/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1195/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1196/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1197/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1198/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1199/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1200/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1201/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1202/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1203/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1204/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1205/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1206/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1207/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1208/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1209/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1210/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1211/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1212/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1213/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1214/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1215/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1216/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1217/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1218/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1219/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1220/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1221/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1222/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1223/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1224/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1225/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1226/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1227/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1228/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1229/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1230/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1231/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1232/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1233/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1234/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1235/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1236/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1237/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1238/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1239/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1240/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1241/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1242/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1243/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1244/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1245/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1246/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1247/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1248/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1249/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1250/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1251/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1252/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1253/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1254/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1255/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1256/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1257/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1258/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1259/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1260/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1261/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1262/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1263/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1264/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1265/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1266/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1267/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1268/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1269/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1270/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1271/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1272/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1273/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1274/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1275/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1276/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1277/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1278/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1279/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1280/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1281/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1282/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1283/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1284/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1285/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1286/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1287/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1288/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1289/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1290/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1291/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1292/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1293/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1294/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1295/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1296/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1297/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1298/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1299/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1300/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1301/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1302/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1303/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1304/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1305/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1306/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1307/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1308/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1309/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1310/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1311/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1312/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1313/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1314/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1315/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1316/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1317/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1318/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1319/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1320/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1321/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1322/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1323/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1324/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1325/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1326/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1327/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1328/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1329/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1330/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1331/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1332/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1333/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1334/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1335/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1336/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1337/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1338/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1339/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1340/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1341/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1342/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1343/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1344/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1345/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1346/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1347/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1348/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1349/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1350/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1351/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1352/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1353/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1354/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1355/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1356/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1357/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1358/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1359/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1360/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1361/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1362/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1363/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1364/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1365/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1366/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1367/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1368/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1369/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1370/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1371/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1372/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1373/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1374/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1375/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1376/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1377/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1378/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1379/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1380/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1381/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1382/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1383/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1384/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1385/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1386/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1387/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1388/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1389/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1390/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1391/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1392/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1393/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1394/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1395/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1396/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1397/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1398/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1399/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1400/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1401/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1402/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1403/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1404/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1405/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1406/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1407/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1408/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1409/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1410/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1411/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1412/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1413/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1414/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1415/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1416/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1417/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1418/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1419/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1420/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1421/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1422/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1423/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1424/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1425/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1426/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1427/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1428/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1429/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1430/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1431/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1432/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1433/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1434/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1435/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1436/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1437/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1438/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1439/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1440/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1441/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1442/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1443/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1444/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1445/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1446/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1447/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1448/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1449/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1450/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1451/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1452/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1453/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1454/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1455/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1456/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1457/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1458/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1459/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1460/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1461/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1462/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1463/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1464/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1465/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1466/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1467/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1468/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1469/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1470/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1471/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1472/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1473/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1474/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1475/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1476/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1477/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1478/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1479/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1480/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1481/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1482/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1483/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1484/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1485/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1486/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1487/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1488/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1489/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1490/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1491/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1492/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1493/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1494/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1495/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1496/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1497/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1498/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1499/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1500/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1501/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1502/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1503/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1504/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1505/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1506/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1507/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1508/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1509/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1510/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1511/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1512/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1513/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1514/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1515/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1516/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1517/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1518/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1519/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1520/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1521/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1522/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1523/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1524/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1525/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1526/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1527/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1528/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1529/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1530/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1531/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1532/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1533/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1534/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1535/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1536/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1537/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1538/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1539/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1540/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1541/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1542/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1543/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1544/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1545/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1546/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1547/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1548/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1549/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1550/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1551/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1552/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1553/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1554/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1555/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1556/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1557/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1558/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1559/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1560/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1561/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1562/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1563/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1564/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1565/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1566/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1567/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1568/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1569/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1570/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1571/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1572/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1573/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1574/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1575/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1576/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1577/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1578/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1579/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1580/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1581/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1582/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1583/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1584/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1585/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1586/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1587/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1588/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1589/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1590/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1591/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1592/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1593/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1594/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1595/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1596/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1597/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1598/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1599/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1600/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1601/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1602/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1603/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1604/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1605/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1606/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1607/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1608/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1609/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1610/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1611/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1612/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1613/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1614/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1615/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1616/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1617/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1618/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1619/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1620/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1621/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1622/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1623/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1624/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1625/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1626/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1627/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1628/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1629/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1630/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1631/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1632/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1633/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1634/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1635/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1636/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1637/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1638/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1639/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1640/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1641/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1642/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1643/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1644/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1645/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1646/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1647/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1648/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1649/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1650/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1651/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1652/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1653/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1654/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1655/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1656/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1657/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1658/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1659/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1660/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1661/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1662/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1663/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1664/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1665/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1666/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1667/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1668/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1669/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1670/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1671/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1672/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1673/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1674/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1675/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1676/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1677/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1678/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1679/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1680/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1681/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1682/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1683/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1684/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1685/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1686/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1687/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1688/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1689/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1690/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1691/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1692/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1693/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1694/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1695/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1696/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1697/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1698/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1699/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1700/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1701/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1702/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1703/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1704/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1705/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1706/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1707/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1708/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1709/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1710/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1711/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1712/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1713/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1714/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1715/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1716/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1717/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1718/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1719/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1720/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1721/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1722/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1723/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1724/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1725/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1726/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1727/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1728/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1729/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1730/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1731/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1732/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1733/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1734/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1735/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1736/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1737/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1738/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1739/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1740/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1741/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1742/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1743/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1744/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1745/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1746/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1747/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1748/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1749/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1750/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1751/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1752/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1753/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1754/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1755/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1756/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1757/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1758/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1759/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1760/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1761/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1762/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1763/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1764/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1765/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1766/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1767/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1768/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1769/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1770/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1771/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1772/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1773/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1774/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1775/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1776/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1777/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1778/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1779/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1780/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1781/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1782/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1783/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1784/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1785/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1786/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1787/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1788/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1789/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1790/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1791/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1792/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1793/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1794/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1795/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1796/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1797/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1798/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1799/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1800/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1801/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1802/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1803/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1804/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1805/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1806/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1807/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1808/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1809/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1810/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1811/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1812/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1813/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1814/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1815/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1816/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1817/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1818/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1819/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1820/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1821/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1822/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1823/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1824/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1825/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1826/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1827/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1828/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1829/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1830/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1831/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1832/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1833/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1834/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1835/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1836/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1837/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1838/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1839/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1840/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1841/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1842/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1843/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1844/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1845/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1846/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1847/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1848/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1849/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1850/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1851/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1852/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1853/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1854/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1855/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1856/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1857/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1858/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1859/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1860/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1861/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1862/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1863/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1864/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1865/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1866/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1867/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1868/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1869/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1870/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1871/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1872/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1873/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1874/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1875/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1876/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1877/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1878/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1879/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1880/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1881/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1882/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1883/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1884/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1885/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1886/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1887/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1888/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1889/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1890/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1891/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1892/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1893/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1894/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1895/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1896/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1897/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1898/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1899/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1900/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1901/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1902/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1903/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1904/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1905/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1906/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1907/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1908/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1909/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1910/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1911/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1912/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1913/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1914/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1915/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1916/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1917/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1918/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1919/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1920/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1921/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1922/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1923/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1924/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1925/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1926/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1927/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1928/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1929/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1930/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1931/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1932/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1933/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1934/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1935/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1936/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1937/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1938/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1939/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1940/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1941/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1942/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1943/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1944/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1945/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1946/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1947/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1948/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1949/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1950/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1951/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1952/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1953/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1954/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1955/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1956/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1957/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1958/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1959/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1960/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1961/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1962/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1963/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1964/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1965/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1966/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1967/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1968/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1969/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1970/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1971/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1972/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1973/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1974/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1975/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1976/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1977/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1978/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1979/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1980/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1981/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1982/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1983/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1984/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1985/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1986/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1987/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1988/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1989/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1990/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1991/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1992/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1993/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1994/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1995/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1996/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1997/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1998/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 1999/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2000/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2001/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2002/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2003/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2004/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2005/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2006/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2007/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2008/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2009/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2010/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2011/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2012/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2013/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2014/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2015/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2016/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2017/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2018/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2019/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2020/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2021/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2022/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2023/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2024/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2025/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2026/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2027/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2028/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2029/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2030/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2031/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2032/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2033/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2034/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2035/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2036/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2037/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2038/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2039/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2040/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2041/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2042/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2043/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2044/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2045/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2046/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2047/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2048/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2049/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2050/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2051/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2052/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2053/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2054/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2055/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2056/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2057/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2058/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2059/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2060/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2061/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2062/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2063/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2064/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2065/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2066/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2067/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2068/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2069/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2070/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2071/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2072/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2073/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2074/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2075/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2076/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2077/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2078/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2079/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2080/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2081/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2082/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2083/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2084/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2085/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2086/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2087/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2088/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2089/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2090/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2091/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2092/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2093/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2094/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2095/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2096/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2097/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2098/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2099/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2100/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2101/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2102/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2103/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2104/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2105/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2106/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2107/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2108/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2109/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2110/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2111/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2112/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2113/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2114/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2115/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2116/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2117/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2118/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2119/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2120/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2121/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2122/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2123/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2124/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2125/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2126/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2127/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2128/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2129/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2130/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2131/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2132/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2133/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2134/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2135/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2136/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2137/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2138/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2139/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2140/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2141/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2142/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2143/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2144/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2145/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2146/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2147/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2148/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2149/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2150/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2151/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2152/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2153/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2154/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2155/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2156/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2157/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2158/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2159/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2160/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2161/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2162/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2163/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2164/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2165/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2166/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2167/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2168/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2169/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2170/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2171/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2172/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2173/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2174/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2175/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2176/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2177/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2178/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2179/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2180/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2181/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2182/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2183/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2184/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2185/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2186/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2187/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2188/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2189/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2190/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2191/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2192/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2193/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2194/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2195/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2196/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2197/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2198/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2199/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2200/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2201/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2202/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2203/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2204/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2205/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2206/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2207/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2208/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2209/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2210/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2211/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2212/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2213/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2214/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2215/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2216/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2217/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2218/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2219/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2220/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2221/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2222/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2223/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2224/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2225/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2226/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2227/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2228/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2229/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2230/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2231/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2232/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2233/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2234/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2235/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2236/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2237/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2238/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2239/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2240/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2241/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2242/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2243/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2244/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2245/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2246/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2247/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2248/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2249/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2250/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2251/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2252/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2253/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2254/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2255/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2256/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2257/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2258/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2259/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2260/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2261/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2262/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2263/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2264/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2265/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2266/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2267/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2268/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2269/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2270/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2271/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2272/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2273/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2274/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2275/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2276/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2277/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2278/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2279/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2280/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2281/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2282/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2283/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2284/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2285/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2286/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2287/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2288/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2289/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2290/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2291/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2292/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2293/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2294/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2295/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2296/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2297/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2298/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2299/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2300/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + " 11: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 12: Publish Instance: /telemetry/data\n", + " 13: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 14: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2301/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2302/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: TelemetryNode::TelemetryNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /telemetry/data\n", + " 7: Callback Instance: RadioNode::RadioNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/telemetry/radio\n", + "\n", + "Path 2303/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2304/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2305/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2306/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2307/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2308/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2309/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2310/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2311/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2312/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2313/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2314/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2315/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2316/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2317/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2318/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2319/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2320/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2321/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2322/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2323/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2324/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2325/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2326/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2327/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2328/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2329/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2330/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2331/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2332/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2333/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2334/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2335/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2336/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2337/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2338/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2339/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2340/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2341/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2342/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2343/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2344/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2345/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2346/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2347/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2348/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2349/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2350/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2351/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2352/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2353/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2354/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2355/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2356/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2357/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2358/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2359/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2360/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2361/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2362/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2363/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2364/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2365/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2366/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2367/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2368/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2369/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2370/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2371/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2372/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2373/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2374/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2375/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2376/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2377/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2378/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2379/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2380/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2381/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2382/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2383/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2384/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2385/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2386/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2387/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2388/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2389/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2390/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2391/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2392/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2393/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2394/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2395/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2396/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2397/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2398/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2399/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2400/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2401/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2402/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2403/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2404/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2405/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2406/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2407/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2408/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2409/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2410/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2411/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2412/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2413/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2414/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2415/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2416/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2417/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2418/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2419/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2420/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2421/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2422/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2423/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2424/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2425/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2426/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2427/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2428/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2429/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2430/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2431/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2432/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2433/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2434/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2435/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2436/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2437/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2438/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2439/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2440/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2441/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2442/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2443/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2444/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2445/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2446/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2447/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2448/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2449/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2450/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2451/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2452/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2453/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2454/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2455/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2456/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2457/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2458/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2459/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2460/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2461/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2462/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2463/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2464/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2465/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2466/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2467/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2468/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2469/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2470/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2471/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2472/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2473/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2474/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2475/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2476/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2477/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2478/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2479/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2480/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2481/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2482/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2483/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2484/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2485/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2486/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2487/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2488/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2489/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2490/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2491/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2492/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2493/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2494/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2495/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2496/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2497/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2498/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2499/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2500/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2501/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2502/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2503/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2504/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2505/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2506/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2507/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2508/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2509/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2510/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2511/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2512/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2513/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2514/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2515/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2516/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2517/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2518/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2519/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2520/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2521/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2522/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2523/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2524/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2525/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2526/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2527/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2528/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2529/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2530/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2531/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2532/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2533/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2534/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2535/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2536/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2537/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2538/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2539/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2540/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2541/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2542/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2543/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2544/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2545/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2546/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2547/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2548/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2549/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2550/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2551/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2552/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2553/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2554/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2555/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2556/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2557/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2558/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2559/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2560/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2561/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2562/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2563/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2564/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2565/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2566/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2567/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2568/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2569/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2570/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2571/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2572/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2573/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2574/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2575/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2576/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2577/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2578/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2579/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2580/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2581/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2582/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2583/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2584/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2585/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2586/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2587/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2588/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2589/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2590/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2591/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2592/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2593/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2594/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2595/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2596/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2597/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2598/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2599/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2600/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2601/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2602/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2603/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2604/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2605/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2606/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2607/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2608/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2609/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2610/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2611/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2612/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2613/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2614/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2615/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2616/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2617/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2618/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2619/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2620/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2621/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2622/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2623/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2624/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2625/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2626/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2627/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2628/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2629/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2630/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2631/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2632/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2633/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2634/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2635/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2636/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2637/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2638/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2639/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2640/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2641/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2642/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2643/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2644/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2645/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2646/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2647/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2648/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2649/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2650/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2651/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2652/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2653/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2654/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2655/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2656/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2657/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2658/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2659/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2660/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2661/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2662/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2663/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2664/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2665/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2666/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2667/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2668/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2669/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2670/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2671/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2672/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2673/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2674/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2675/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2676/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2677/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2678/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2679/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2680/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2681/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2682/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2683/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2684/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2685/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2686/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2687/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2688/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2689/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2690/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2691/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2692/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2693/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2694/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2695/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2696/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2697/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2698/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2699/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2700/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2701/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2702/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2703/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2704/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2705/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2706/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2707/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2708/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2709/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2710/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2711/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2712/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2713/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2714/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2715/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2716/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2717/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2718/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2719/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2720/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2721/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2722/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2723/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2724/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2725/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2726/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2727/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2728/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2729/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2730/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2731/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2732/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2733/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2734/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2735/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2736/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2737/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2738/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2739/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2740/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2741/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2742/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2743/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2744/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2745/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2746/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2747/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2748/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2749/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2750/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2751/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2752/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2753/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2754/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2755/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2756/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2757/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2758/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2759/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2760/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2761/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2762/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2763/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2764/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2765/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2766/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2767/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2768/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2769/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2770/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2771/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2772/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2773/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2774/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2775/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2776/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2777/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2778/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2779/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2780/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2781/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2782/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2783/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2784/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2785/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2786/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2787/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2788/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2789/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2790/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2791/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2792/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2793/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2794/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2795/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2796/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2797/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2798/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2799/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2800/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2801/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: GeometricNode::GeometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /camera/geometric\n", + " 9: Callback Instance: MappingNode::MappingNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 10: Publish Instance: /output/camera/mapped\n", + "\n", + "Path 2802/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2803/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2804/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2805/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2806/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2807/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2808/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2809/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2810/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2811/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2812/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2813/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2814/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2815/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2816/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2817/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2818/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2819/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2820/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2821/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2822/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2823/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2824/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2825/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2826/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2827/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2828/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2829/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2830/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2831/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2832/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2833/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2834/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2835/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2836/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2837/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2838/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2839/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2840/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2841/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2842/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2843/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2844/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2845/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2846/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2847/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2848/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2849/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2850/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2851/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2852/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2853/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2854/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2855/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2856/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2857/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2858/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2859/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2860/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2861/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2862/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2863/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2864/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2865/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2866/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2867/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2868/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2869/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2870/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2871/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2872/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2873/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2874/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2875/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2876/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2877/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2878/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2879/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2880/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2881/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2882/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2883/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2884/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2885/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2886/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2887/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2888/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2889/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2890/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2891/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2892/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2893/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2894/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2895/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2896/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2897/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2898/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2899/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2900/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2901/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2902/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2903/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2904/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2905/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2906/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2907/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2908/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2909/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2910/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2911/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2912/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2913/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2914/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2915/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2916/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2917/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2918/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2919/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2920/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2921/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2922/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2923/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2924/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2925/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2926/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2927/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2928/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2929/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2930/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2931/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2932/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2933/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2934/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2935/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2936/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2937/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2938/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2939/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2940/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2941/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2942/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2943/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2944/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2945/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2946/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2947/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2948/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2949/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2950/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2951/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2952/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2953/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2954/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2955/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2956/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2957/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2958/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2959/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2960/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2961/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2962/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2963/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2964/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2965/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2966/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2967/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2968/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2969/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2970/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2971/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2972/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2973/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2974/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2975/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2976/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2977/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2978/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2979/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2980/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2981/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2982/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2983/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2984/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2985/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2986/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2987/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2988/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2989/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2990/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2991/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2992/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2993/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2994/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2995/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2996/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2997/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2998/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 2999/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3000/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3001/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3002/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3003/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3004/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3005/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3006/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3007/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3008/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3009/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3010/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3011/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3012/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3013/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3014/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3015/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3016/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3017/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3018/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3019/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3020/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3021/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3022/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3023/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3024/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3025/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3026/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3027/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3028/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3029/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3030/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3031/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3032/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3033/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3034/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3035/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3036/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3037/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3038/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3039/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3040/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3041/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3042/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3043/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3044/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3045/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3046/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3047/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3048/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3049/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3050/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3051/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3052/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3053/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3054/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3055/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3056/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3057/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3058/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3059/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3060/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3061/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3062/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3063/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3064/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3065/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3066/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3067/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3068/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3069/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3070/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3071/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3072/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3073/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3074/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3075/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3076/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3077/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3078/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3079/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3080/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3081/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3082/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3083/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3084/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3085/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3086/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3087/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3088/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3089/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3090/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3091/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3092/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3093/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3094/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3095/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3096/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3097/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3098/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3099/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3100/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3101/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3102/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3103/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3104/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3105/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3106/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3107/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3108/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3109/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3110/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3111/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3112/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3113/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3114/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3115/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3116/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3117/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3118/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3119/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3120/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3121/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3122/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3123/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3124/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3125/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3126/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3127/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3128/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3129/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3130/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3131/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3132/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3133/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3134/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3135/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3136/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3137/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3138/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3139/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3140/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3141/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3142/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3143/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3144/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3145/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3146/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3147/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3148/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3149/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3150/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3151/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3152/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3153/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3154/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3155/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3156/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3157/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3158/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3159/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3160/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3161/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3162/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3163/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3164/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3165/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3166/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3167/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3168/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3169/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3170/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3171/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3172/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3173/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3174/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3175/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3176/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3177/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3178/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3179/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3180/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3181/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3182/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3183/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3184/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3185/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3186/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3187/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3188/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3189/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3190/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3191/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3192/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3193/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3194/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3195/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3196/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3197/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3198/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3199/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3200/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3201/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3202/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3203/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3204/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3205/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3206/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3207/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3208/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3209/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3210/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3211/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3212/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3213/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3214/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3215/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3216/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3217/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3218/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3219/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3220/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3221/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3222/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3223/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3224/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3225/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3226/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3227/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3228/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3229/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3230/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3231/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3232/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3233/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3234/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3235/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3236/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3237/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3238/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3239/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3240/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3241/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3242/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3243/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3244/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3245/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3246/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3247/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3248/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3249/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3250/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3251/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3252/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3253/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3254/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3255/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3256/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3257/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3258/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3259/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3260/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3261/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3262/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3263/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3264/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3265/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3266/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3267/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3268/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3269/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3270/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3271/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3272/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3273/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3274/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3275/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3276/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3277/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3278/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3279/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3280/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3281/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3282/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3283/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3284/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3285/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3286/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3287/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3288/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3289/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3290/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3291/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3292/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3293/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3294/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3295/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3296/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3297/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3298/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3299/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3300/6895:\n", + " 1: Callback Instance: CameraNode::CameraNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/camera/raw\n", + " 3: Callback Instance: DebayerNode::DebayerNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /camera/debayered\n", + " 5: Callback Instance: RadiometricNode::RadiometricNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /camera/radiometric\n", + " 7: Callback Instance: SmokeClassifierNode::SmokeClassifierNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/classifier/classification\n", + "\n", + "Path 3301/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3302/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3303/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3304/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3305/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3306/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3307/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3308/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3309/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3310/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3311/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3312/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3313/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3314/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3315/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3316/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3317/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3318/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3319/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3320/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3321/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3322/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3323/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3324/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3325/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3326/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3327/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3328/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3329/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3330/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3331/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3332/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3333/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3334/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3335/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3336/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3337/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3338/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3339/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3340/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3341/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3342/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3343/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3344/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3345/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3346/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3347/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3348/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3349/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3350/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3351/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3352/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3353/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3354/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3355/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3356/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3357/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3358/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3359/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3360/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3361/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3362/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3363/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3364/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3365/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3366/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3367/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3368/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3369/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3370/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3371/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3372/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3373/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3374/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3375/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3376/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3377/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3378/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3379/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3380/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3381/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3382/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3383/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3384/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3385/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3386/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3387/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3388/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3389/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3390/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3391/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3392/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3393/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3394/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3395/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3396/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3397/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3398/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3399/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3400/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3401/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3402/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3403/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3404/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3405/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3406/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3407/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3408/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3409/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3410/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3411/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3412/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3413/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3414/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3415/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3416/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3417/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3418/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3419/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3420/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3421/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3422/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3423/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3424/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3425/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3426/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3427/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3428/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3429/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3430/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3431/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3432/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3433/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3434/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3435/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3436/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3437/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3438/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3439/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3440/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3441/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3442/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3443/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3444/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3445/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3446/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3447/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3448/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3449/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3450/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3451/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3452/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3453/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3454/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3455/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3456/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3457/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3458/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3459/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3460/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3461/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3462/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3463/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3464/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3465/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3466/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3467/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3468/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3469/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3470/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3471/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3472/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3473/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3474/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3475/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3476/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3477/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3478/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3479/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3480/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3481/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3482/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3483/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3484/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3485/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3486/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3487/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3488/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3489/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3490/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3491/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3492/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3493/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3494/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3495/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3496/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3497/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3498/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3499/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3500/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3501/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3502/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3503/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3504/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3505/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3506/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3507/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3508/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3509/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3510/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3511/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3512/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3513/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3514/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3515/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3516/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3517/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3518/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3519/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3520/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3521/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3522/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3523/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3524/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3525/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3526/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3527/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3528/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3529/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3530/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3531/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3532/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3533/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3534/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3535/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3536/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3537/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3538/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3539/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3540/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3541/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3542/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3543/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3544/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3545/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3546/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3547/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3548/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3549/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3550/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3551/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3552/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3553/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3554/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3555/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3556/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3557/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3558/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3559/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3560/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3561/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3562/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3563/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3564/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3565/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3566/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3567/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3568/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3569/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3570/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3571/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3572/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3573/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3574/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3575/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3576/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3577/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3578/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3579/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3580/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3581/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3582/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3583/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3584/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3585/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3586/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3587/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3588/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3589/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3590/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3591/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3592/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3593/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3594/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3595/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3596/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3597/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3598/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3599/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3600/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3601/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3602/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3603/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3604/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3605/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3606/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3607/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3608/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3609/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3610/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3611/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3612/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3613/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3614/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3615/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3616/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3617/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3618/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3619/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3620/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3621/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3622/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3623/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3624/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3625/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3626/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3627/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3628/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3629/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3630/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3631/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3632/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3633/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3634/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3635/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3636/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3637/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3638/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3639/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3640/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3641/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3642/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3643/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3644/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3645/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3646/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3647/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3648/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3649/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3650/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3651/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3652/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3653/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3654/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3655/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3656/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3657/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3658/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3659/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3660/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3661/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3662/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3663/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3664/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3665/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3666/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3667/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3668/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3669/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3670/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3671/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3672/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3673/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3674/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3675/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3676/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3677/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3678/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3679/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3680/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3681/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3682/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3683/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3684/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3685/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3686/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3687/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3688/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3689/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3690/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3691/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3692/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3693/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3694/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3695/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3696/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3697/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3698/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3699/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3700/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3701/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3702/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3703/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3704/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3705/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3706/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3707/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3708/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3709/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3710/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3711/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3712/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3713/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3714/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3715/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3716/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3717/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3718/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3719/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3720/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3721/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3722/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3723/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3724/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3725/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3726/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3727/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3728/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3729/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3730/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3731/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3732/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3733/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3734/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3735/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3736/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3737/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3738/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3739/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3740/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3741/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3742/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3743/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3744/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3745/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3746/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3747/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3748/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3749/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3750/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3751/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3752/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3753/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3754/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3755/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3756/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3757/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3758/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3759/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3760/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3761/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3762/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3763/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3764/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3765/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3766/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3767/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3768/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3769/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3770/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3771/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3772/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3773/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3774/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3775/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3776/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3777/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3778/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3779/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3780/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3781/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3782/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3783/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3784/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3785/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3786/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3787/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3788/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3789/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3790/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3791/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3792/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3793/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3794/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3795/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3796/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3797/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3798/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3799/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3800/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3801/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3802/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3803/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3804/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3805/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3806/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3807/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3808/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3809/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3810/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3811/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3812/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3813/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3814/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3815/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3816/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3817/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3818/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3819/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3820/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3821/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3822/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3823/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3824/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3825/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3826/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3827/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3828/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3829/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3830/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3831/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3832/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3833/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3834/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3835/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3836/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3837/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3838/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3839/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3840/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3841/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3842/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3843/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3844/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3845/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3846/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3847/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3848/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3849/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3850/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3851/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3852/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3853/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3854/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3855/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3856/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3857/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3858/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3859/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3860/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3861/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3862/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3863/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3864/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3865/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3866/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3867/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3868/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3869/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3870/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3871/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3872/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3873/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3874/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3875/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3876/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3877/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3878/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3879/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3880/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3881/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3882/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3883/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3884/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3885/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3886/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3887/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3888/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3889/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3890/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3891/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3892/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3893/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3894/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3895/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3896/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3897/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3898/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3899/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3900/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3901/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3902/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3903/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3904/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3905/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3906/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3907/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3908/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3909/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3910/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3911/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3912/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3913/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3914/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3915/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3916/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3917/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3918/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3919/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3920/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3921/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3922/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3923/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3924/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3925/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3926/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3927/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3928/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3929/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3930/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3931/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3932/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3933/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3934/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3935/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3936/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3937/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3938/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3939/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3940/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3941/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3942/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3943/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3944/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3945/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3946/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3947/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3948/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3949/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3950/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3951/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3952/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3953/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3954/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3955/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3956/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3957/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3958/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3959/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3960/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3961/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3962/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3963/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3964/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3965/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3966/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3967/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3968/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3969/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3970/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3971/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3972/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3973/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3974/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3975/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3976/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3977/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3978/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3979/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3980/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3981/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3982/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3983/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3984/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3985/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3986/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3987/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3988/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3989/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3990/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3991/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3992/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3993/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3994/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3995/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3996/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3997/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3998/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 3999/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4000/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4001/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4002/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4003/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4004/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4005/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4006/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4007/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4008/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4009/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4010/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4011/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4012/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4013/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4014/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4015/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4016/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4017/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4018/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4019/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4020/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4021/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4022/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4023/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4024/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4025/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4026/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4027/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4028/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4029/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4030/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4031/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4032/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4033/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4034/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4035/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4036/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4037/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4038/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4039/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4040/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4041/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4042/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4043/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4044/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4045/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4046/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4047/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4048/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4049/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4050/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4051/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4052/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4053/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4054/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4055/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4056/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4057/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4058/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4059/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4060/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4061/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4062/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4063/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4064/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4065/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4066/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4067/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4068/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4069/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4070/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4071/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4072/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4073/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4074/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4075/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4076/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4077/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4078/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4079/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4080/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4081/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4082/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4083/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4084/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4085/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4086/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4087/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4088/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4089/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4090/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4091/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4092/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4093/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4094/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4095/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4096/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4097/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4098/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4099/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4100/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4101/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4102/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4103/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4104/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4105/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4106/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4107/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4108/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4109/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4110/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4111/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4112/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4113/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4114/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4115/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4116/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4117/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4118/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4119/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4120/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4121/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4122/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4123/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4124/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4125/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4126/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4127/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4128/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4129/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4130/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4131/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4132/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4133/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4134/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4135/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4136/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4137/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4138/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4139/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4140/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4141/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4142/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4143/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4144/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4145/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4146/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4147/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4148/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4149/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4150/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4151/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4152/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4153/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4154/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4155/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4156/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4157/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4158/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4159/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4160/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4161/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4162/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4163/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4164/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4165/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4166/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4167/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4168/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4169/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4170/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4171/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4172/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4173/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4174/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4175/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4176/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4177/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4178/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4179/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4180/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4181/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4182/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4183/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4184/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4185/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4186/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4187/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4188/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4189/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4190/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4191/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4192/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4193/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4194/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4195/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4196/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4197/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4198/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4199/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4200/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4201/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4202/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4203/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4204/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4205/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4206/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4207/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4208/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4209/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4210/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4211/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4212/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4213/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4214/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4215/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4216/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4217/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4218/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4219/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4220/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4221/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4222/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4223/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4224/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4225/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4226/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4227/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4228/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4229/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4230/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4231/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4232/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4233/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4234/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4235/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4236/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4237/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4238/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4239/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4240/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4241/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4242/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4243/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4244/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4245/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4246/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4247/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4248/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4249/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4250/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4251/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4252/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4253/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4254/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4255/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4256/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4257/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4258/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4259/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4260/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4261/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4262/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4263/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4264/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4265/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4266/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4267/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4268/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4269/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4270/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4271/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4272/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4273/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4274/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4275/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4276/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4277/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4278/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4279/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4280/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4281/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4282/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4283/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4284/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4285/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4286/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4287/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4288/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4289/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4290/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4291/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4292/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4293/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4294/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4295/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4296/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4297/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4298/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4299/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4300/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4301/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4302/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4303/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4304/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4305/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4306/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4307/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4308/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4309/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4310/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4311/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4312/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4313/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4314/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4315/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4316/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4317/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4318/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4319/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4320/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4321/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4322/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4323/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4324/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4325/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4326/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4327/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4328/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4329/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4330/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4331/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4332/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4333/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4334/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4335/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4336/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4337/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4338/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4339/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4340/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4341/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4342/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4343/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4344/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4345/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4346/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4347/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4348/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4349/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4350/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4351/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4352/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4353/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4354/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4355/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4356/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4357/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4358/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4359/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4360/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4361/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4362/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4363/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4364/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4365/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4366/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4367/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4368/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4369/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4370/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4371/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4372/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4373/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4374/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4375/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4376/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4377/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4378/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4379/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4380/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4381/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4382/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4383/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4384/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4385/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4386/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4387/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4388/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4389/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4390/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4391/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4392/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4393/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4394/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4395/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4396/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4397/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4398/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4399/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4400/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4401/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4402/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4403/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4404/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4405/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4406/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4407/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4408/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4409/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4410/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4411/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4412/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4413/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4414/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4415/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4416/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4417/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4418/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4419/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4420/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4421/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4422/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4423/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4424/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4425/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4426/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4427/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4428/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4429/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4430/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4431/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4432/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4433/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4434/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4435/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4436/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4437/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4438/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4439/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4440/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4441/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4442/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4443/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4444/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4445/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4446/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4447/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4448/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4449/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4450/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4451/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4452/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4453/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4454/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4455/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4456/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4457/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4458/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4459/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4460/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4461/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4462/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4463/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4464/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4465/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4466/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4467/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4468/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4469/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4470/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4471/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4472/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4473/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4474/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4475/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4476/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4477/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4478/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4479/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4480/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4481/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4482/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4483/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4484/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4485/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4486/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4487/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4488/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4489/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4490/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4491/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4492/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4493/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4494/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4495/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4496/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4497/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4498/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4499/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4500/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4501/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4502/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4503/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4504/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4505/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4506/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4507/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4508/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4509/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4510/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4511/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4512/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4513/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4514/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4515/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4516/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4517/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4518/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4519/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4520/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4521/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4522/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4523/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4524/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4525/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4526/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4527/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4528/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4529/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4530/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4531/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4532/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4533/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4534/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4535/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4536/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4537/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4538/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4539/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4540/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4541/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4542/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4543/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4544/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4545/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4546/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4547/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4548/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4549/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4550/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4551/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4552/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4553/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4554/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4555/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4556/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4557/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4558/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4559/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4560/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4561/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4562/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4563/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4564/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4565/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4566/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4567/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4568/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4569/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4570/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4571/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4572/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4573/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4574/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4575/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4576/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4577/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4578/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4579/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4580/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4581/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4582/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4583/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4584/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4585/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4586/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4587/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4588/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4589/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4590/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4591/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4592/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4593/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4594/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4595/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4596/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4597/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4598/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4599/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4600/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4601/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4602/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4603/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4604/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4605/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4606/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4607/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4608/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4609/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4610/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4611/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4612/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4613/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4614/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4615/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4616/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4617/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4618/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4619/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4620/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4621/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4622/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4623/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4624/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4625/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4626/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4627/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4628/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4629/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4630/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4631/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4632/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4633/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4634/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4635/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4636/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4637/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4638/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4639/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4640/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4641/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4642/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4643/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4644/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4645/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4646/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4647/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4648/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4649/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4650/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4651/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4652/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4653/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4654/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4655/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4656/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4657/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4658/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4659/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4660/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4661/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4662/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4663/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4664/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4665/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4666/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4667/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4668/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4669/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4670/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4671/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4672/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4673/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4674/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4675/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4676/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4677/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4678/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4679/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4680/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4681/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4682/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4683/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4684/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4685/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4686/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4687/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4688/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4689/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4690/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4691/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4692/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4693/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4694/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4695/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4696/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4697/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4698/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4699/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4700/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4701/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4702/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4703/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4704/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4705/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4706/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4707/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4708/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4709/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4710/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4711/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4712/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4713/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4714/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4715/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4716/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4717/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4718/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4719/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4720/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4721/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4722/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4723/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4724/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4725/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4726/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4727/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4728/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4729/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4730/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4731/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4732/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4733/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4734/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4735/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4736/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4737/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4738/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4739/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4740/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4741/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4742/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4743/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4744/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4745/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4746/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4747/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4748/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4749/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4750/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4751/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4752/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4753/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4754/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4755/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4756/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4757/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4758/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4759/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4760/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4761/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4762/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4763/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4764/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4765/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4766/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4767/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4768/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4769/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4770/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4771/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4772/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4773/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4774/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4775/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4776/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4777/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4778/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4779/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4780/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4781/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4782/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4783/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4784/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4785/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4786/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4787/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4788/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4789/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4790/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4791/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4792/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4793/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4794/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4795/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4796/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4797/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4798/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4799/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4800/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4801/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4802/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4803/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4804/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4805/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4806/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4807/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4808/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4809/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4810/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4811/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4812/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4813/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4814/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4815/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4816/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4817/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4818/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4819/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4820/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4821/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4822/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4823/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4824/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4825/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4826/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4827/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4828/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4829/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4830/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4831/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4832/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4833/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4834/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4835/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4836/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4837/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4838/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4839/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4840/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4841/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4842/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4843/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4844/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4845/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4846/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4847/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4848/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4849/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4850/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4851/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4852/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4853/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4854/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4855/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4856/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4857/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4858/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4859/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4860/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4861/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4862/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4863/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4864/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4865/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4866/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4867/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4868/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4869/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4870/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4871/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4872/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4873/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4874/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4875/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4876/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4877/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4878/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4879/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4880/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4881/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4882/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4883/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4884/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4885/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4886/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4887/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4888/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4889/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4890/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4891/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4892/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4893/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4894/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4895/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4896/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4897/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4898/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4899/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4900/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4901/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4902/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4903/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4904/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4905/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4906/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4907/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4908/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4909/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4910/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4911/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4912/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4913/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4914/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4915/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4916/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4917/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4918/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4919/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4920/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4921/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4922/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4923/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4924/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4925/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4926/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4927/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4928/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4929/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4930/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4931/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4932/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4933/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4934/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4935/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4936/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4937/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4938/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4939/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4940/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4941/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4942/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4943/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4944/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4945/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4946/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4947/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4948/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4949/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4950/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4951/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4952/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4953/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4954/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4955/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4956/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4957/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4958/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4959/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4960/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4961/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4962/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4963/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4964/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4965/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4966/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4967/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4968/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4969/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4970/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4971/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4972/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4973/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4974/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4975/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4976/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4977/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4978/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4979/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4980/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4981/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4982/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4983/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4984/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4985/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4986/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4987/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4988/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4989/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4990/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4991/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4992/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4993/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4994/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4995/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4996/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4997/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4998/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 4999/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5000/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5001/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5002/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5003/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5004/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5005/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5006/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5007/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5008/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5009/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5010/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5011/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5012/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5013/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5014/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5015/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5016/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5017/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5018/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5019/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5020/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5021/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5022/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5023/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5024/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5025/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5026/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5027/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5028/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5029/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5030/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5031/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5032/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5033/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5034/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5035/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5036/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5037/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5038/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5039/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5040/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5041/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5042/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5043/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5044/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5045/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5046/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5047/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5048/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5049/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5050/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5051/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5052/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5053/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5054/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5055/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5056/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5057/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5058/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5059/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5060/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5061/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5062/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5063/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5064/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5065/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5066/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5067/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5068/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5069/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5070/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5071/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5072/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5073/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5074/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5075/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5076/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5077/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5078/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5079/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5080/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5081/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5082/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5083/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5084/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5085/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5086/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5087/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5088/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5089/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5090/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5091/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5092/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5093/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5094/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5095/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5096/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5097/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5098/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5099/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5100/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5101/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5102/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5103/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5104/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5105/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5106/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5107/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5108/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5109/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5110/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5111/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5112/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5113/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5114/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5115/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5116/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5117/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5118/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5119/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5120/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5121/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5122/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5123/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5124/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5125/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5126/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5127/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5128/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5129/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5130/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5131/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5132/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5133/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5134/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5135/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5136/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5137/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5138/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5139/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5140/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5141/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5142/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5143/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5144/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5145/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5146/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5147/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5148/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5149/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5150/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5151/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5152/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5153/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5154/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5155/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5156/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5157/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5158/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5159/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5160/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5161/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5162/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5163/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5164/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5165/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5166/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5167/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5168/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5169/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5170/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5171/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5172/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5173/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5174/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5175/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5176/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5177/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5178/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5179/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5180/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5181/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5182/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5183/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5184/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5185/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5186/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5187/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5188/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5189/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5190/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5191/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5192/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5193/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5194/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5195/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5196/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5197/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5198/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5199/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5200/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5201/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5202/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5203/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5204/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5205/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5206/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5207/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5208/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5209/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5210/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5211/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5212/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5213/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5214/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5215/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5216/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5217/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5218/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5219/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5220/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5221/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5222/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5223/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5224/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5225/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5226/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5227/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5228/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5229/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5230/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5231/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5232/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5233/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5234/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5235/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5236/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5237/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5238/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5239/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5240/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5241/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5242/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5243/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5244/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5245/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5246/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5247/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5248/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5249/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5250/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5251/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5252/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5253/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5254/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5255/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5256/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5257/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5258/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5259/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5260/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5261/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5262/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5263/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5264/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5265/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5266/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5267/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5268/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5269/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5270/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5271/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5272/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5273/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5274/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5275/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5276/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5277/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5278/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5279/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5280/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5281/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5282/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5283/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5284/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5285/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5286/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5287/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5288/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5289/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5290/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5291/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5292/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5293/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5294/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5295/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5296/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5297/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5298/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5299/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5300/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5301/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5302/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5303/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5304/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5305/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5306/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5307/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5308/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5309/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5310/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5311/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5312/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5313/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5314/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5315/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5316/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5317/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5318/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5319/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5320/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5321/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5322/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5323/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5324/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5325/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5326/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5327/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5328/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5329/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5330/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5331/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5332/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5333/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5334/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5335/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5336/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5337/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5338/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5339/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5340/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5341/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5342/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5343/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5344/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5345/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5346/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5347/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5348/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5349/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5350/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5351/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5352/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5353/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5354/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5355/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5356/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5357/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5358/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5359/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5360/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5361/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5362/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5363/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5364/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5365/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5366/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5367/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5368/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5369/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5370/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5371/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5372/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5373/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5374/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5375/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5376/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5377/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5378/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5379/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5380/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5381/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5382/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5383/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5384/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5385/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5386/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5387/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5388/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5389/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5390/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5391/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5392/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5393/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5394/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5395/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5396/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5397/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5398/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5399/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5400/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5401/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5402/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5403/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5404/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5405/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5406/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5407/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5408/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5409/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5410/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5411/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5412/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5413/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5414/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5415/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5416/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5417/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5418/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5419/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5420/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5421/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5422/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5423/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5424/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5425/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5426/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5427/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5428/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5429/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5430/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5431/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5432/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5433/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5434/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5435/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5436/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5437/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5438/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5439/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5440/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5441/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5442/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5443/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5444/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5445/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5446/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5447/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5448/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5449/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5450/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5451/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5452/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5453/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5454/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5455/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5456/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5457/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5458/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5459/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5460/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5461/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5462/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5463/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5464/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5465/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5466/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5467/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5468/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5469/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5470/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5471/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5472/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5473/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5474/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5475/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5476/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5477/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5478/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5479/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5480/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5481/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5482/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5483/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5484/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5485/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5486/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5487/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5488/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5489/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5490/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5491/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5492/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5493/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5494/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5495/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5496/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5497/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5498/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5499/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5500/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5501/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5502/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5503/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5504/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5505/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5506/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5507/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5508/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5509/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5510/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5511/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5512/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5513/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5514/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5515/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5516/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5517/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5518/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5519/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5520/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5521/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5522/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5523/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5524/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5525/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5526/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5527/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5528/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5529/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5530/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5531/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5532/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5533/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5534/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5535/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5536/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5537/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5538/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5539/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5540/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5541/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5542/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5543/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5544/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5545/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5546/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5547/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5548/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5549/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5550/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5551/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5552/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5553/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5554/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5555/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5556/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5557/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5558/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5559/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5560/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5561/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5562/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5563/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5564/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5565/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5566/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5567/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5568/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5569/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5570/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5571/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5572/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5573/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5574/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5575/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5576/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5577/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5578/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5579/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5580/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5581/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5582/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5583/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5584/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5585/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5586/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5587/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5588/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5589/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5590/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5591/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5592/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5593/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5594/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5595/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5596/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5597/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5598/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5599/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5600/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5601/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5602/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5603/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5604/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5605/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5606/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5607/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5608/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5609/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5610/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5611/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5612/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5613/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5614/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5615/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5616/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5617/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5618/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5619/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5620/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5621/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5622/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5623/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5624/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5625/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5626/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5627/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5628/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5629/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5630/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5631/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5632/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5633/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5634/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5635/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5636/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5637/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5638/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5639/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5640/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5641/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5642/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5643/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5644/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5645/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5646/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5647/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5648/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5649/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5650/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5651/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5652/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5653/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5654/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5655/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5656/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5657/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5658/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5659/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5660/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5661/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5662/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5663/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5664/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5665/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5666/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5667/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5668/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5669/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5670/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5671/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5672/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5673/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5674/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5675/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5676/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5677/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5678/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5679/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5680/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5681/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5682/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5683/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5684/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5685/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5686/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5687/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5688/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5689/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5690/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5691/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5692/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5693/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5694/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5695/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5696/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5697/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5698/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5699/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5700/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5701/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5702/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5703/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5704/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5705/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5706/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5707/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5708/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5709/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5710/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5711/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5712/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5713/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5714/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5715/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5716/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5717/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5718/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5719/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5720/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5721/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5722/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5723/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5724/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5725/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5726/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5727/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5728/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5729/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5730/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5731/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5732/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5733/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5734/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5735/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5736/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5737/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5738/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5739/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5740/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5741/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5742/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5743/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5744/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5745/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5746/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5747/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5748/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5749/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5750/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5751/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5752/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5753/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5754/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5755/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5756/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5757/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5758/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5759/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5760/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5761/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5762/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5763/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5764/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5765/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5766/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5767/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5768/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5769/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5770/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5771/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5772/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5773/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5774/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5775/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5776/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5777/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5778/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5779/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5780/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5781/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5782/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5783/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5784/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5785/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5786/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5787/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5788/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5789/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5790/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5791/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5792/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5793/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5794/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5795/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5796/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5797/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5798/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5799/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5800/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5801/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5802/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5803/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5804/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5805/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5806/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5807/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5808/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5809/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5810/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5811/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5812/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5813/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5814/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5815/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5816/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5817/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5818/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5819/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5820/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5821/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5822/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5823/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5824/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5825/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5826/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5827/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5828/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5829/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5830/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5831/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5832/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5833/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5834/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5835/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5836/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5837/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5838/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5839/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5840/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5841/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5842/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5843/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5844/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5845/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5846/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5847/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5848/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5849/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5850/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5851/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5852/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5853/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5854/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5855/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5856/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5857/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5858/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5859/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5860/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5861/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5862/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5863/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5864/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5865/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5866/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5867/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5868/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5869/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5870/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5871/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5872/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5873/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5874/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5875/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5876/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5877/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5878/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5879/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5880/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5881/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5882/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5883/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5884/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5885/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5886/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5887/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5888/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5889/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5890/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5891/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5892/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5893/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5894/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5895/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5896/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5897/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5898/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5899/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5900/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5901/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5902/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5903/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5904/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5905/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5906/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5907/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5908/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5909/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5910/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5911/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5912/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5913/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5914/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5915/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5916/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5917/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5918/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5919/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5920/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5921/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5922/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5923/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5924/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5925/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5926/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5927/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5928/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5929/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5930/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5931/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5932/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5933/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5934/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5935/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5936/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5937/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5938/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5939/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5940/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5941/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5942/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5943/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5944/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5945/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5946/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5947/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5948/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5949/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5950/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5951/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5952/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5953/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5954/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5955/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5956/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5957/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5958/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5959/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5960/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5961/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5962/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5963/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5964/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5965/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5966/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5967/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5968/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5969/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5970/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5971/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5972/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5973/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5974/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5975/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5976/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5977/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5978/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5979/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5980/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5981/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5982/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5983/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5984/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5985/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5986/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5987/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5988/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5989/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5990/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5991/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5992/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5993/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5994/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5995/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5996/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5997/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5998/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 5999/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6000/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6001/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6002/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6003/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6004/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6005/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6006/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6007/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6008/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6009/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6010/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6011/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6012/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6013/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6014/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6015/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6016/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6017/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6018/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6019/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6020/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6021/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6022/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6023/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6024/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6025/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6026/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6027/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6028/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6029/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6030/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6031/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6032/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6033/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6034/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6035/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6036/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6037/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6038/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6039/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6040/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6041/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6042/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6043/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6044/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6045/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6046/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6047/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6048/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6049/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6050/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6051/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6052/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6053/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6054/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6055/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6056/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6057/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6058/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6059/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6060/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6061/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6062/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6063/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6064/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6065/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6066/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6067/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6068/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6069/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6070/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6071/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6072/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6073/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6074/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6075/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6076/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6077/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6078/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6079/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6080/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6081/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6082/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6083/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6084/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6085/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6086/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6087/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6088/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6089/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6090/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6091/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6092/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6093/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6094/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6095/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6096/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6097/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6098/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6099/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6100/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6101/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6102/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6103/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6104/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6105/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6106/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6107/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6108/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6109/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6110/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6111/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6112/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6113/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6114/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6115/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6116/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6117/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6118/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6119/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6120/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6121/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6122/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6123/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6124/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6125/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6126/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6127/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6128/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6129/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6130/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6131/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6132/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6133/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6134/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6135/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6136/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6137/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6138/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6139/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6140/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6141/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6142/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6143/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6144/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6145/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6146/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6147/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6148/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6149/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6150/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6151/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6152/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6153/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6154/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6155/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6156/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6157/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6158/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6159/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6160/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6161/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6162/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6163/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6164/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6165/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6166/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6167/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6168/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6169/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6170/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6171/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6172/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6173/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6174/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6175/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6176/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6177/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6178/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6179/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6180/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6181/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6182/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6183/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6184/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6185/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6186/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6187/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6188/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6189/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6190/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6191/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6192/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6193/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6194/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6195/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6196/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6197/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6198/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6199/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6200/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6201/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6202/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6203/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6204/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6205/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6206/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6207/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6208/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6209/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6210/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6211/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6212/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6213/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6214/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6215/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6216/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6217/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6218/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6219/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6220/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6221/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6222/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6223/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6224/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6225/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6226/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6227/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6228/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6229/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6230/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6231/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6232/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6233/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6234/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6235/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6236/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6237/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6238/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6239/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6240/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6241/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6242/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6243/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6244/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6245/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6246/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6247/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6248/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6249/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6250/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6251/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6252/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6253/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6254/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6255/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6256/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6257/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6258/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6259/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6260/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6261/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6262/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6263/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6264/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6265/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6266/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6267/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6268/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6269/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6270/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6271/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6272/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6273/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6274/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6275/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6276/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6277/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6278/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6279/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6280/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6281/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6282/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6283/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6284/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6285/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6286/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6287/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6288/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6289/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6290/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6291/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6292/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6293/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6294/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6295/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6296/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6297/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6298/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6299/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6300/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6301/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6302/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6303/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6304/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6305/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6306/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6307/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6308/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6309/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6310/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6311/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6312/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6313/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6314/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6315/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6316/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6317/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6318/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6319/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6320/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6321/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6322/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6323/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6324/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6325/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6326/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6327/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6328/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6329/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6330/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6331/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6332/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6333/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6334/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6335/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6336/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6337/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6338/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6339/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6340/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6341/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6342/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6343/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6344/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6345/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6346/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6347/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6348/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6349/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6350/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6351/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6352/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6353/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6354/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6355/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6356/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6357/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6358/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6359/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6360/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6361/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6362/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6363/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6364/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6365/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6366/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6367/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6368/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6369/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6370/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6371/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6372/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6373/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6374/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6375/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6376/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6377/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6378/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6379/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6380/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6381/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6382/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6383/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6384/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6385/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6386/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6387/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6388/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6389/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6390/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6391/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6392/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6393/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6394/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6395/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6396/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6397/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6398/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6399/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6400/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6401/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6402/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6403/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6404/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6405/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6406/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6407/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6408/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6409/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6410/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6411/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6412/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6413/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6414/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6415/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6416/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6417/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6418/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6419/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6420/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6421/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6422/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6423/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6424/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6425/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6426/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6427/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6428/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6429/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6430/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6431/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6432/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6433/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6434/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6435/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6436/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6437/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6438/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6439/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6440/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6441/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6442/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6443/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6444/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6445/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6446/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6447/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6448/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6449/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6450/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6451/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6452/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6453/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6454/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6455/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6456/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6457/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6458/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6459/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6460/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6461/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6462/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6463/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6464/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6465/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6466/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6467/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6468/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6469/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6470/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6471/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6472/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6473/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6474/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6475/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6476/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6477/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6478/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6479/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6480/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6481/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6482/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6483/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6484/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6485/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6486/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6487/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6488/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6489/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6490/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6491/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6492/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6493/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6494/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6495/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6496/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6497/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6498/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6499/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6500/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6501/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6502/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6503/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6504/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6505/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6506/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6507/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6508/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6509/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6510/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6511/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6512/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6513/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6514/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6515/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6516/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6517/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6518/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6519/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6520/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6521/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6522/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6523/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6524/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6525/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6526/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6527/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6528/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6529/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6530/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6531/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6532/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6533/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6534/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6535/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6536/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6537/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6538/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6539/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6540/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6541/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6542/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6543/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6544/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6545/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6546/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6547/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6548/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6549/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6550/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6551/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6552/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6553/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6554/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6555/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6556/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6557/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6558/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6559/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6560/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6561/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6562/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6563/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6564/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6565/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6566/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6567/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6568/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6569/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6570/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6571/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6572/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6573/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6574/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6575/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6576/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6577/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6578/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6579/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6580/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6581/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6582/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6583/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6584/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6585/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6586/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6587/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6588/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6589/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6590/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6591/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6592/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6593/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6594/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6595/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6596/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6597/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6598/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6599/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6600/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6601/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6602/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6603/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6604/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6605/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6606/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6607/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6608/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6609/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6610/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6611/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6612/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6613/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6614/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6615/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6616/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6617/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6618/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6619/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6620/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6621/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6622/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6623/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6624/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6625/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6626/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6627/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6628/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6629/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6630/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6631/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6632/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6633/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6634/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6635/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6636/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6637/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6638/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6639/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6640/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6641/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6642/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6643/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6644/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6645/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6646/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6647/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6648/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6649/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6650/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6651/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6652/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6653/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6654/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6655/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6656/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6657/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6658/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6659/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6660/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6661/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6662/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6663/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6664/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6665/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6666/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6667/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6668/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6669/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6670/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6671/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6672/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6673/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6674/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6675/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6676/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6677/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6678/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6679/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6680/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6681/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6682/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6683/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6684/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6685/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6686/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6687/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6688/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6689/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6690/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6691/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6692/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6693/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6694/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6695/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6696/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6697/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6698/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6699/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6700/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6701/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6702/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6703/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6704/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6705/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6706/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6707/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6708/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6709/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6710/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6711/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6712/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6713/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6714/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6715/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6716/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6717/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6718/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6719/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6720/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6721/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6722/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6723/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6724/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6725/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6726/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6727/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6728/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6729/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6730/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6731/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6732/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6733/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6734/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6735/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6736/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6737/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6738/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6739/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6740/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6741/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6742/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6743/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6744/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6745/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6746/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6747/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6748/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6749/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6750/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6751/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6752/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6753/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6754/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6755/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6756/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6757/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6758/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6759/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6760/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6761/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6762/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6763/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6764/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6765/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6766/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6767/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6768/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6769/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6770/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6771/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6772/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6773/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6774/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6775/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6776/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6777/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6778/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6779/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6780/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6781/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6782/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6783/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6784/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6785/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6786/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6787/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6788/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6789/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6790/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6791/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6792/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6793/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6794/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6795/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6796/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6797/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6798/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6799/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6800/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6801/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6802/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6803/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6804/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6805/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6806/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6807/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6808/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6809/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6810/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6811/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6812/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6813/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6814/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6815/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6816/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6817/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6818/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6819/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6820/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6821/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6822/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6823/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6824/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6825/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6826/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6827/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6828/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6829/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6830/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6831/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6832/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6833/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6834/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6835/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6836/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6837/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6838/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6839/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6840/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6841/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6842/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6843/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6844/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6845/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6846/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6847/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6848/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6849/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6850/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6851/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6852/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6853/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6854/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6855/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6856/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6857/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6858/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6859/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6860/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6861/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6862/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6863/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6864/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6865/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6866/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6867/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6868/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6869/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6870/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6871/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6872/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6873/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6874/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6875/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6876/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6877/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6878/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6879/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6880/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6881/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6882/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6883/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6884/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6885/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6886/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6887/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6888/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6889/6895:\n", + " 1: Callback Instance: IMUNode::IMUNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/imu/data\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6890/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6891/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6892/6895:\n", + " 1: Callback Instance: CommandNode::CommandNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/operator/commands\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6893/6895:\n", + " 1: Callback Instance: GPSNode::GPSNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/gps/fix\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6894/6895:\n", + " 1: Callback Instance: LidarNode::LidarNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/lidar/scan\n", + " 3: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /flight/plan\n", + " 5: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /output/flight/cmd\n", + "\n", + "Path 6895/6895:\n", + " 1: Callback Instance: BaroNode::BaroNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda()#1}\n", + " 2: Publish Instance: /input/baro/alt\n", + " 3: Callback Instance: FusionNode::FusionNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 4: Publish Instance: /sensors/fused\n", + " 5: Callback Instance: FlightManagementNode::FlightManagementNode(std::__cxx11::basic_string, std::allocator > const&, std::vector, std::allocator >, std::allocator, std::allocator > > > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 6: Publish Instance: /flight/plan\n", + " 7: Callback Instance: ControlNode::ControlNode(std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, std::__cxx11::basic_string, std::allocator > const&, int, double)::{lambda(std::shared_ptr > >)#1}\n", + " 8: Publish Instance: /output/flight/cmd\n", + "\n", + "Found 6895 E2E paths in total.\n" + ] + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "\n", "from message_tree.message_tree_algorithms import e2e_paths_sorted_desc\n", "from message_tree.message_tree_algorithms import owner\n", + "from message_tree.message_tree_structure import DepTree\n", + "\n", + "# set of seen publush topics to avoid duplicates\n", + "seen_publish_topics = set()\n", + "\n", + "def _print_elem(elem, indent=0):\n", + " if isinstance(elem, TrTopic):\n", + " print(f\"{' ' * indent}Topic: {elem.name}\")\n", + " elif isinstance(elem, TrCallbackObject):\n", + " print(f\"{' ' * indent}Callback: {elem.name} ({elem.elem.name})\")\n", + " elif isinstance(elem, TrPublishInstance):\n", + " #if elem.publisher.topic_name in seen_publish_topics:\n", + " # print(f\"{' ' * indent}Publish Instance: {elem.publisher.topic_name} (already seen)\")\n", + " # return False\n", + " #seen_publish_topics.add(elem.publisher.topic_name)\n", + " print(f\"{' ' * indent}Publish Instance: {elem.publisher.topic_name}\")\n", + " elif isinstance(elem, TrCallbackInstance):\n", + " print(f\"{' ' * indent}Callback Instance: {elem.callback_obj.callback_symbol.symbol}\")\n", + " else:\n", + " print(f\"{' ' * indent}Unknown element type: {type(elem)}\")\n", + " return True\n", + "\n", + "def _traverse_print_tree(tree, indent=0):\n", + " \"\"\"Recursively traverse a dependency tree and print its structure.\"\"\"\n", + " for i, node in enumerate(tree):\n", + " if isinstance(node, DepTree):\n", + " if not _print_elem(node.head, indent):\n", + " continue\n", + " _traverse_print_tree(node.deps, indent + 2)\n", + " elif isinstance(node, list):\n", + " for entry in node:\n", + " if entry is not None and isinstance(entry, DepTree):\n", + " if not _print_elem(entry.head, indent):\n", + " continue\n", + " _traverse_print_tree(entry.deps, indent + 2)\n", + " else:\n", + " print(f\"{' ' * indent}List of {len(node)} elements, but not a DepTree.\")\n", + " else:\n", + " if not _print_elem(node, indent):\n", + " continue\n", + "\n", + "def _print_trees():\n", + " print(\"Dependency Trees:\")\n", + " for i, tree in enumerate(trees):\n", + " print(f\"\\nTree {i + 1}/{len(trees)}:\")\n", + " _traverse_print_tree(tree)\n", + " print(\"\\nEnd of Dependency Trees\\n\")\n", + " print(f\"Published topics seen so far: {len(seen_publish_topics)}:, {', '.join(seen_publish_topics)}\")\n", + "_print_trees()\n", + "\n", "\n", "##################################################\n", "# Find and filter relevant E2E paths in trees\n", "##################################################\n", + "trees_paths = [e2e_paths_sorted_desc(tree, E2E_INPUT_TOPIC_PATTERNS) for tree in tqdm(trees, mininterval=10.0, desc=\"Extracting E2E paths\")]\n", + "all_paths = [p for paths in trees_paths for p in paths]\n", "\n", - "trees_paths = [e2e_paths_sorted_desc(tree, E2E_INPUT_TOPIC_PATTERNS) for tree in tqdm(trees, mininterval=10.0,\n", - " desc=\"Extracting E2E paths\")]\n", - "all_paths = [p for paths in trees_paths for p in paths]" + "def _print_paths():\n", + " for i, path in enumerate(all_paths):\n", + " print(f\"Path {i+1}/{len(all_paths)}:\")\n", + " for j, elem in enumerate(path):\n", + " if isinstance(elem, TrTopic):\n", + " print(f\" {j+1:>3d}: Topic: {elem.name}\")\n", + " elif isinstance(elem, TrCallbackObject):\n", + " print(f\" {j+1:>3d}: Callback: {elem.name} ({elem.node.name})\")\n", + " elif isinstance(elem, TrPublishInstance):\n", + " print(f\" {j+1:>3d}: Publish Instance: {elem.publisher.topic_name}\")\n", + " elif isinstance(elem, TrCallbackInstance):\n", + " print(f\" {j+1:>3d}: Callback Instance: {elem.callback_obj.callback_symbol.symbol}\")\n", + " else:\n", + " print(f\" {j+1:>3d}: Unknown element type: {elem}\")\n", + " print()\n", + "_print_paths()\n", + "\n", + "print(f\"Found {len(all_paths)} E2E paths in total.\")" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 12, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Aggregating E2E path cohorts: 100%|██████████| 6895/6895 [00:00<00:00, 79394.40it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Found 11 cohorts of E2E paths.\n" + ] + }, + { + "data": { + "text/html": [ + "
\n", + "\n", + "\n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + " \n", + "
pathe2e_latency
countmeanminmax
10void(LidarNode::LidarNode(std::__cxx11::basic_...9970.0394740.0251450.086360
5void(CommandNode::CommandNode(std::__cxx11::ba...7970.0431630.0237640.114404
6void(GPSNode::GPSNode(std::__cxx11::basic_stri...7050.0507110.0364030.085157
7void(GPSNode::GPSNode(std::__cxx11::basic_stri...6990.0259320.0172090.053311
1void(BaroNode::BaroNode(std::__cxx11::basic_st...6010.0265030.0182930.054396
0void(BaroNode::BaroNode(std::__cxx11::basic_st...5960.0513220.0372650.091714
9void(IMUNode::IMUNode(std::__cxx11::basic_stri...5040.0264190.0192790.056391
8void(IMUNode::IMUNode(std::__cxx11::basic_stri...5000.0486170.0363050.081712
2void(CameraNode::CameraNode(std::__cxx11::basi...4990.0689420.0578910.084229
4void(CameraNode::CameraNode(std::__cxx11::basi...4990.0760060.0652360.089868
3void(CameraNode::CameraNode(std::__cxx11::basi...4980.0797070.0668430.104887
\n", + "
" + ], + "text/plain": [ + " path e2e_latency \\\n", + " count mean \n", + "10 void(LidarNode::LidarNode(std::__cxx11::basic_... 997 0.039474 \n", + "5 void(CommandNode::CommandNode(std::__cxx11::ba... 797 0.043163 \n", + "6 void(GPSNode::GPSNode(std::__cxx11::basic_stri... 705 0.050711 \n", + "7 void(GPSNode::GPSNode(std::__cxx11::basic_stri... 699 0.025932 \n", + "1 void(BaroNode::BaroNode(std::__cxx11::basic_st... 601 0.026503 \n", + "0 void(BaroNode::BaroNode(std::__cxx11::basic_st... 596 0.051322 \n", + "9 void(IMUNode::IMUNode(std::__cxx11::basic_stri... 504 0.026419 \n", + "8 void(IMUNode::IMUNode(std::__cxx11::basic_stri... 500 0.048617 \n", + "2 void(CameraNode::CameraNode(std::__cxx11::basi... 499 0.068942 \n", + "4 void(CameraNode::CameraNode(std::__cxx11::basi... 499 0.076006 \n", + "3 void(CameraNode::CameraNode(std::__cxx11::basi... 498 0.079707 \n", + "\n", + " \n", + " min max \n", + "10 0.025145 0.086360 \n", + "5 0.023764 0.114404 \n", + "6 0.036403 0.085157 \n", + "7 0.017209 0.053311 \n", + "1 0.018293 0.054396 \n", + "0 0.037265 0.091714 \n", + "9 0.019279 0.056391 \n", + "8 0.036305 0.081712 \n", + "2 0.057891 0.084229 \n", + "4 0.065236 0.089868 \n", + "3 0.066843 0.104887 " + ] + }, + "execution_count": 12, + "metadata": {}, + "output_type": "execute_result" + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "\n", @@ -499,7 +166060,8 @@ "# Group dataflows by DFG path\n", "##################################################\n", "\n", - "cohorts = aggregate_e2e_paths(all_paths) #all_paths)\n", + "cohorts = aggregate_e2e_paths(all_paths)\n", + "print(f\"Found {len(cohorts)} cohorts of E2E paths.\")\n", "cohort_pairs = [(k, v) for k, v in cohorts.items()]\n", "cohort_pairs.sort(key=lambda kv: len(kv[1]), reverse=True)\n", "\n", @@ -520,7 +166082,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 13, "metadata": { "collapsed": false }, @@ -535,12 +166097,243 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 14, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/tmp/ipykernel_328981/283584388.py:53: RuntimeWarning: More than 20 figures have been opened. Figures created through the pyplot interface (`matplotlib.pyplot.figure`) are retained until explicitly closed and may consume too much memory. (To control this warning, see the rcParam `figure.max_open_warning`). Consider using `matplotlib.pyplot.close()`.\n", + " fig, axes = plt.subplots(1, 3, num=f\"E2E type breakdown histograms {name}\", dpi=300, figsize=(16, 9))\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAD4UAAAnqCAYAAACKGDemAAAAOnRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjEwLjMsIGh0dHBzOi8vbWF0cGxvdGxpYi5vcmcvZiW1igAAAAlwSFlzAAAuIwAALiMBeKU/dgABAABJREFUeJzs3Xd4FFX/9/FPCi0k1JBQpIP0DoJICV2qgAhIF1HBetvwttw0u4hdAUUBEQsgSBUBDUjvvXcktCQQQoD0ef7wIT92Z5Psbja7m/B+XddeMGfnlN2ZPXNmMt85PoZhGAIAAAAAAAAAAAAAAAAAAAAAAAAAAAAAeCVfTzcAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJA+gsIBAAAAAAAAAAAAAAAAAAAAAAAAAAAAwIsRFA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAXoygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAADwYgSFAwAAAAAAAAAAAAAAAAAAAAAAAAAAAIAXIygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAALwYQeEAAAAAAAAAAAAAAAAAAAAAAAAAAAAA4MUICgcAAAAAAAAAAAAAAAAAAAAAAAAAAAAAL0ZQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAB4MYLCAQAAAAAAAAAAAAAAAAAAAAAAAAAAAMCLERQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAF6MoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA8GIEhQMAAAAAAAAAAAAAAAAAAAAAAAAAAACAFyMoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC8GEHhAAAAAAAAAAAAAAAAAAAAAAAAAAAAAODFCAoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC9GUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAeDGCwgEAAAAAAAAAAAAAAAAAAAAAAAAAAADAixEUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAABejKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPBiBIUDAAAAAAAAAAAAAAAAAAAAAAAAAAAAgBcjKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvBhB4QAAAAAAAAAAAAAAAAAAAAAAAAAAAADgxQgKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvRlA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAHgxgsIBAAAAAAAAAAAAAAAAAAAAAAAAAAAAwIsRFA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAXoygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAADwYgSFAwAAAAAAAAAAAAAAAAAAAAAAAAAAAIAXIygcAAAAAAAAAJBrVKhQQT4+PmmvYcOGebpJdgsLC7Noe1hYmKebBA9avXq1xf7g4+Oj1atXe7pZAADkWozF4A7W47tx48Zlaz5X8XT9AABkt/j4eM2YMUODBg1SjRo1FBwcLH9/f4vjX5EiRSzyOHvtJqde82G8jJwiJ/+NAAAAAAAAe/h7ugEAAAAAAAC3JCYm6vDhwzp48KCioqJ09epV5cmTR0WLFlWJEiXUqFEjlSlTxtPNBAAAAAAAAAAAQC7w22+/6fHHH1dkZKSnmwIAAAAAAABkiqBwAAAAAADuUKdOnVLFihWzpezChQsrJiYm0/WSkpK0evVq/fnnnwoPD9eOHTuUnJycYZ677rpLDz30kEaNGqWqVas63cawsDCtWbPG6fwZWbBggXr27JktZUv/ziLRpk0bi7ShQ4dqxowZ2VYnkNsNGzZMM2fOdChPvnz5VKhQIRUtWlTVq1dX/fr11alTJzVv3jybWgkAyIwj/bmvr68CAwNVuHBhBQcHq27dumrYsKG6du2qypUrZ3NLAVgbN26cxo8f75G6p0+fzsxhAAAAwB1o1qxZGjJkiKebAQAAAAAAANjN19MNAAAAAAAAd549e/bo0UcfVWhoqDp27Kj3339fW7ZsyTQgXJLOnj2rjz/+WNWqVdOIESMUGxvrhhbDU3x8fCxe48aN83STgDQJCQmKjIzUkSNHtGjRIk2YMEH33XefKleurO+++06GYXi6iQCADKSmpio2Nlb//POPdu7cqZkzZ+q5555T1apVFRYWpvDwcE83EQAAZKBChQoW1wx4uAMAwBEcR1wnLCzM4rsMCwvzdJPsEhERoZEjR9p8r0yZMqpTp47q1auX9qpTp46bW4jb8fciAAAAAACAfxEUDgAAAAAA3G7+/Pn67rvvdOXKFafLMAxD3377rerUqaMjR464sHUAkDUnTpzQo48+qtatW2epnwMAeIZhGFqzZo3atWunUaNG2fXgIgAAAAAAkLN89dVXunHjhkXa8OHDdfbsWZ09e1Z79uzRrl270l5r1671UEsBAAAAAACA/+Pv6QYAAAAAAADvUbBgQVWpUiXL5QQFBTmVL1++fGrSpImaN2+u0qVLKyQkRCkpKTp//rw2bNig33//XQkJCRZ5zpw5o7Zt22rt2rWqWLFiltpdo0YN5c2bN0tlSFLhwoWzXAYAz6tcubICAwNtvmcYhuLi4hQVFaXY2Fib66xdu1ZhYWFau3atChUqlJ1NBQBkIL3+PDU1VTExMbp48aISExNN7xuGoSlTpujmzZuaPn26fHx83NFc4I5VsmRJ1atXz6E8Z86cMT2Ep2zZsipWrJhD5Ti6PgAAAICc77fffrNYvueeezRt2jTO/wEAAAAAAODVCAoHAAAAAABpGjdurNWrV7u1Tn9/f3Xp0kWPPPKI7r//fuXPnz/ddc+fP6+XX35Zs2fPtkiPiIjQ8OHDFR4enqW2LFu2TBUqVMhSGQByj2nTpiksLCzT9U6fPq2FCxfqo48+0unTpy3e27Nnj1577TV98cUX2dRKAEBmMuvPExIStHXrVk2bNk2zZs1SamqqxfszZ85Uq1atNHz48GxuKXBnGzlypEaOHOlQnmHDhmnmzJkWaRMmTNCwYcNc2DLcKdx9PQRwhGEYnm4CAAC5yrVr13To0CGLtL59+7olIDwsLIxjOwAAAAAAAJzm6+kGAAAAAACAO1OBAgX0/PPP659//tHChQvVs2fPDAPCJalUqVL64YcfNGHCBNN7q1ev1q+//ppdzQWAdJUvX17PPvusDhw4oM6dO5venzx5ss6dO+eBlgEA7JEvXz61aNFCM2bM0IoVKxQQEGBaZ+zYsYqPj/dA6wAAAAAAgKudPXvW9FC4atWqeag1AAAAAAAAgP0ICgcAAAAAAG53//3368SJE/roo49UsmRJh/P/73//U7du3Uzp33//vSuaBwBOCQgI0C+//GLq11JTU7VgwQIPtQoA4Ih27dpp8uTJpvSzZ88qPDzcAy0CAAAAAACudvXqVVNawYIFPdASAAAAAAAAwDEEhQMAAAAAALdr1qyZU8Hgtxs/frwpbcWKFUpMTMxSuQCQFUFBQRoyZIgpfefOnR5oDQDAGYMGDVKVKlVM6StWrPBAawAAAAAAgKvFx8eb0nx8fDzQEgAAAAAAAMAx/p5uAAAAAAAAgDMaNmyokiVL6sKFC2lp8fHxOn/+vMqXL+/Blt0ZEhMTdezYMR06dEgXLlxQbGysJKlYsWIqVqyY6tSpo2rVqnm4lY65ceOGNm/erAsXLigyMlLXr19X8eLFVaJECdWvX18VK1bM9jZcvXpVmzZt0tGjR3X16lUFBgaqRIkSatiwoapXr55t9R49elQHDx5UVFSUoqKilJqaqqCgIJUuXVrVq1fX3XffLT8/v2yrP7dp0qSJKe32vsoVLl26pG3btunkyZO6evWqfHx8FBwcrF69eik4ONiuMhITE7V161ZFRETo0qVLio2NVdGiRVWiRAnVrFlTNWvWdGmbDcPQ6dOndejQIZ05c0axsbFKTExUkSJFVLRoUVWuXFkNGzaUv3/uuWwdHR2tTZs2KSIiQpGRkSpQoIDKlSunRo0auaVPMQxDe/fu1dGjRxUZGanLly+rcOHCCgkJUcWKFdWwYUP5+vLsWEmKjIzUpk2bdOLECcXFxaV9T02bNvX6cUV8fLw2b96sQ4cO6cqVK8qTJ49Kly6tu+++Ww0bNuSGZif4+vqqU6dOOnbsmEX6gQMHslz2xYsXtWPHDkVGRurSpUtKTU1ViRIlFBoaqmbNmqlYsWJZruOWlJQUHT16VHv37lVkZKRiY2OVkpKigIAAFSpUSGXLllXFihVVuXJll/UFMTEx2rJlS9p4KiUlRSEhIQoJCVGTJk1UokQJl9TjzW7cuKEtW7bo6NGjunz5spKTk1W4cGG1adNGtWrVsrscd47PYmJitHXrVl28eFGRkZFKSEhQcHBw2nYrVaqUS+qB/a5du5Z2XhATE6OAgACVLl1atWrVcmg/cpQ7+6g70dGjR7V9+3ZFREQoISFBxYsXV+nSpdWiRQsVLVo0W+v21D4F73X8+HHt3r1bERERio2NVaFChVS5cmU1bdpUxYsXz7Z6ve288MyZM9q5c6dOnz6ta9euyc/PT6GhoerXr58CAgLc0oaMXLt2TXv37tWRI0cUExOjuLg45cmTRwEBAQoODlb58uVVtWpVl46xDMPQ/v37dfToUUVHRysqKko+Pj5p48caNWqoUqVKWTrPSElJ0YkTJ3To0KG0fTAlJUVFixZV0aJFVb16ddWpU8dt56ue7J+9HdcVXI9zeGSH1NRUbd26VcePH9f58+eVlJSkYsWKqXr16mratKny5cvn1vbk5Ots7pSYmKht27bp7Nmzio6O1pUrV5QvX760cVnNmjWz/IBtW44ePaodO3bo7Nmzio+PV6FChVSjRg3de++9KliwoF1lGIah3bt3a/fu3bp06ZJSUlIUGhqqmjVr6p577nF5XxYREaFt27bp3Llzunz5sgoWLKiKFSuqSZMmKl26tEvrAgAAAAAgRzAAAAAAAMAd6eTJk4Yki1fr1q093SyHNGnSxPQZNm3aZFfe1q1bm/KePHkyexvsIuHh4aa2Dx06NNvr3blzpzF27FijVatWRr58+UxtsH6VKFHCeOSRR4wDBw7YXYetz+boq3z58nbXl5SUZHzzzTdG27Ztjbx582ZYbuXKlY1XX33ViI6Odvi7Gzp0aIZt3Llzp/Hggw8aefLkyfBzff7550ZiYqLD9duya9cuY/jw4UbZsmUz/U6LFCli9O7d2/j555+NhIQEU1l//vmnKc/YsWOz3MZ69epZlBkSEmKzflew3kaSjPDwcKfK+uOPP0xlde7c2a681n3T7f1yamqqMXv2bKNZs2aGj4+PzW2VWZtTU1ONuXPnGl27djUKFiyY4XYvXbq08dRTTxn//POPU9+DYRjGP//8Y3z66adGjx49jKJFi2a6rwUEBBidO3c2/vjjD6frLF++fJb6x9TUVGP06NE2fwd//fWXXWWsXr3auP/++w1/f/90P2udOnWMGTNmGKmpqWn5Mtr+jjh8+LDx6KOPGiVLlszw+y5evLgxYMAAY8eOHQ6VX6pUKYtyHnvsMbvzvv/++zbbEhERYVf+pKQko1ChQhZ5X3755XTXz+w7DQ8PNzp06GD4+vqm+z3VrFnT+OGHHyy2lTvYOibe/hs/fvy48cgjjxgBAQHptr1cuXLG66+/bsTFxdlVJ/35//noo49M5TRs2NCpNl2+fNkYN26c0aBBg3T7b0mGr6+v0bhxY2PKlClZOt5v27bNePTRR43ChQtn2u9KMgoVKmS0b9/e+Pjjj53q85OSkoyvv/7aaNGiheHn55duPT4+Pkbjxo2NSZMmGfHx8Q7XM336dFOZzo7fndnPx44da8p3uw0bNhi9evVKd5xsTx2uHJ9l5saNG8akSZOMe++9N8PtJsmoVauW8d5779ndl7iTrd/89OnT012/ZcuWFusGBgYasbGxWWrDggULTG345JNPbK6b2X5867wgo3OT6tWrGxMnTnTZeYG7+yhv5uxYLKPfe0pKivHdd98ZtWvXTve79fPzM9q1a2ds3LjR4TZ7ep/K6tj7lsz62FtsXcty5uVJzhwfspLvdqmpqca0adOMhg0bZrg/durUyfj7779dVr+3nRcmJiYaX331lVGnTp102+DJa4TJycnGjBkzjDZt2mR4nnL7q2LFisbgwYONBQsWGDdv3nSq3jVr1hj9+/c3QkJCMq0vNDTUGDhwoLF06VIjJSXFrvIPHz5svPvuu0bHjh0zvR4hyShcuLDRp08fu6/12uLJ/jmny+7rCrfkpuOIJ87hb+eqa0qOnHe54rt0Z39raz9x5GXrO81su6fH2XzWoqKijOeeey7D32pgYKDx2GOPWXzXztbv7uts7v57kTskJycb33//vdGpU6cM+4Nbr2rVqhnPPfecXf1sRn1qcnKyMWXKFKN69eoZ7ivPPPNMhn8Di42NNcaPH2+UKVMm3XJCQ0ONDz/80EhKSsry9zV//nyjZcuW6Z6r+vj4GM2bNzcWLlxo93cBAAAAAEBuQFA4AAAAAAB3qNwQFF6rVi3TZ9i9e7ddeQkKt9/BgweNu+++2+mbbnx8fIwRI0bYFfzjzpt8FixYYFSpUsXh8gsVKmR88cUXDn2H6QWFp6amGm+88UamgTi3vxo0aGBcvHjRofpvd+LECaNnz54ZBnxk9KpTp47NcmvUqGGxXpkyZYzk5GSn27lhwwZT3a+++qrT5WXGlUHhs2fPNpU1ZMgQu/Kmd2PdhQsXjFatWmW6fTJq899//53hzf/pvfLly2f873//s/tG71tatGjh9H4myWjevLlTwYlZueHr5s2bRt++fW32K/v37880/40bN4xHH33Uoc/dunVrIzIy0jCMrN/Ae/36dWPUqFEZBqPbevn4+BiDBg0yLl++bFc9gwYNsshfsWJFu9vYoUMHm22YOXOmXfnXr19vyptRsEh632l8fLwxYsQIh76njh07ujUgMqMbdL/77jujQIECdre9XLlyxqpVq+yql/78X19//bWpnCpVqjhURnJysvHuu+8aRYoUcbgPrFixorF69WqH6ouPjzcef/xxu4OHbL2aNm3qUJ2rVq0yqlWr5nA95cqVM+bPn+9QXd4aFJ6YmGg89dRTmfb9GdWRXeOz9HzzzTemB3zY8woNDTXmzp3rUF3ZzdGg8J9//tm0/uTJk7PUho4dO1qUFxAQYFy5csXmuhntx2+99ZZDx/DatWs7HYBlGO7vo3ICVweFnz171rj33nsd+m5fe+01h9rs6X0qNwXzuYsjxwdX5LvlxIkTRosWLRz6np555pm0caCz9XvbeeGRI0cyDAK2/h252+7du426detmaf929Li2a9cuIywszOn6unfvnmH5UVFRRoMGDbL0mR544IF0j60ZSW+/dUf/nFO567rCLbnpOOKpc/hbCArPXG4LCv/555+N4sWL293+ggULGjNmzMhS/e6+zpbbgsLnzZvn1N+kbr0mTZqUYfnp9akRERFG06ZN7a7nrrvusvm31vXr1xvlypWzu5ymTZs6dfw2DMOIjIw0HnjgAYe+n4ceesi4fv16ht8FAAAAAAC5ha8AAAAAAAByoJSUFJ08edKUXqpUKQ+0Jne7cOGCjhw54nR+wzA0bdo0tWrVSrGxsS5smfPtGTt2rHr16qVjx445nD82NlZPP/20nnjiCaWkpDjdjtTUVA0ePFhvvfWWQ+Xs3LlTrVq1UlxcnMN1hoeHq0mTJvrtt99kGIbD+SWluw2feuopi+WIiAgtWrTIqTokafLkyRbLvr6+evzxx50uz53Wrl1rSqtfv77T5V24cEHNmzfX33//7XQZX3/9tdq2basdO3Y4nDchIUFvvvmmevXqpevXr9udb926dU7vZ5K0YcMGNW7cWLt373a6DEdERUWpXbt2mjNnjkV6o0aNtGnTJtWsWTPD/Ddv3lT37t317bffOvS516xZo1atWunKlStOtfuWqKgotW3bVpMnT1ZycrJDeQ3D0A8//KAWLVrozJkzma7fvn17i+WTJ0/qxIkTmeZLSEjQunXrbL63atUqu9pqvV6+fPnUsmVLu/LeEh8fr86dO2vatGkO5VuxYoW6dOmSpb7fFSZPnqzhw4fr5s2bduc5c+aMunTpoqVLl2a6Lv35v2JiYkxpQUFBdue/du2aevTooVdffdVmWZk5efKkOnTooO+++86u9RMTE9W1a1d9/fXXSk1Ndbg+Z0yfPl3333+/Dh8+7HDeM2fO6MEHH9TEiROzoWXuk5KSoj59+ujLL790+piXneMza0lJSRoxYoQee+wxnT9/3uF6Ll68qL59++rNN990OK+36N27t+mc0bqfcsSxY8e0cuVKi7T+/furSJEiDpXzyiuv6I033nDoGL5v3z61adNG27Ztc6guyf191J3oxIkTatq0qTZu3OhQvnfeeUdvvPFGlut39z4F73bixAm1atUq3bF4ej7//HMNHjw4S+d13nReeOjQId17773at29flsvKDtu3b1fr1q21Z88et9X5yy+/qHnz5lq9erXTZWQ2Drl27Zp27tzpdPmStHDhQt1zzz06e/ZslsqRPN8/ezN3Xle4k2T3OTzuTFOnTtXDDz+s6Ohou/Ncv35dw4YN05QpU1zalpx+nc0dUlNT9fLLL6tPnz5O/U3qFmf+vnbu3Dk1b95cmzdvtjvP2bNn1bFjR/3zzz9paStWrFD79u0d6uM3b96s+++/3+FjSnR0tNq1a6eFCxc6lG/u3Lnq3LmzEhMTHcoHAAAAAEBO5O/pBgAAAAAAADjj999/140bNyzSypcvrxIlSnioRXeOokWLqkmTJqpRo4YqV66sQoUKKTAwUDdv3lRUVJT279+vFStWmG4O2bJlix577DH98ssv6ZYdGBioevXqpS1b3/QbGhqqkiVLZti+0qVLZ/j+qFGjNHXqVFN6sWLF1KFDBzVq1EghISEKCAhQTEyM9u/fr+XLl5sCnr7++msVKVJE77//fob1pef111/X7Nmz05bLli2rrl27qk6dOgoODlZcXJwOHjyoX3/91fQAhMOHD+u///2vvvjiC7vrW7p0qXr27GnzBpzg4GC1b99ejRs3VokSJZQ/f37FxMTozJkz2rZtmzZs2KBr165lWP6QIUP06quvWqw3efJk9erVy+423hIdHa25c+dapHXu3FkVKlRwuCx3O3v2rGbNmmWR5uPjo549ezpVXmpqqvr27WsRcFupUiV17dpV1atXV3BwsKKjo3Xy5En9+uuvNst477339Oqrr5rSCxYsqA4dOqhJkyYqVaqUgoKCdPXqVR09elQrV640BZAvWrRIjz76qH7++WeHP0e+fPnUuHFj1axZU9WqVVPRokUVFBSk5ORkXb16VYcOHdK6deu0fft2i3wXL15Unz59tH37dhUqVMjheu119OhRdenSxXRTXrdu3fTzzz+rYMGCmZbRv39//fnnn6b04sWLq1evXqpXr55CQkIUHR2t/fv3a/78+WkBeQcPHtSQIUOcbv/NmzfVpk0bm8ENwcHB6tWrl+rWrZtW/62+5dy5cxbrHjhwQC1atNCuXbtUrFixdOuzDgqX/g3WzizQd/369eneBO1sUHjz5s1VoEABu/LeMnz4cIWHh6ctV6tWTZ07d1b16tVVrFgxXb16VTt37tSvv/6qixcvWuT9+++/9fHHH+ull15yqE5X2bRpk0Uggr+/v9q2bav27durTJkySkhI0OnTp7Vo0SJT4EViYqIefPBBrV69Ws2aNUu3Dvrzf9kKxqlcubJdeW/cuKGwsDCbD+KoXLmy2rRpo7p166pYsWLy9/dXVFSUtm7dqmXLlikyMjJt3VsBvKGhoeratWuGdb777rs2+6CyZcuqY8eOqlmzpkJDQ5U/f37duHFDsbGxOnbsmPbt26eNGzc69NAPSZo1a5aGDx9uSvfx8dG9996rzp07q2zZsvL391dERIRWrlyp8PBwi5u9DcPQ6NGj5ePj47HfVFaNGTPG4qEJxYoVU+fOndWkSROFhITo5s2bOnv2rH7//Xf5+PiY8mf3+Ox2qamp6tmzp5YtW2Z6r3Tp0mrXrp0aNGig4OBg5c+fX5cvX9bOnTv1+++/W4zrDcPQmDFjFBwcrFGjRtldv7fIkyePnnjiCY0bNy4tbc+ePdqwYYOaN2/ucHlTp041BTs6+r3MnTtXH3zwQdpy/vz51blzZ7Vs2VKlSpVSXFycjh8/rgULFpjOSa5evaoOHTpo+/btqlSpkl31eaKPutNcu3ZNnTt3VkREhKR/+8bmzZurffv2KleunAIDAxUZGan169drwYIFio+Pt8j/3nvvqXv37mratKlT9bt7n3KnvHnzWlwzOHDggJKSktKWixYtqnLlynmiaV7rypUratOmjc1g2ipVqqh3796qUqWKChUqpAsXLmjDhg1aunRp2tjgp59+UqNGjVzSFk+eF964cUM9evSwCJ6rXbu2OnfurMqVK6to0aK6dOmSjhw5Yhq/ukNCQoIGDRpkelDHrbFVixYt0q7B+fn5KTY2VtHR0Tpw4IB2796t3bt3Oxx8P3XqVI0cOdLme2XKlFHHjh1Vp04dlShRQnny5NGVK1d04sQJbdu2TRs3bjT1XfYKDAxMu65YtWpVFS5cWEFBQUpMTNSVK1d04MABhYeH6+DBgxb5jh49qn79+mnNmjXy93fudjdP98/ezN3XFTzF3ccRd5zDe9Lt3+WxY8cszisLFiyoKlWqZFpG3rx5s6VttpQsWdKizbfGRLerXLmyAgMDbea35/O4w4IFCzRq1ChTv+/n56eWLVuqY8eOKlOmjPz8/HTu3DmFh4frzz//TAuUffrpp/XWW2+5rD3ZeZ3NHX8vcofBgwfrxx9/tPle7dq11aFDB1WuXFnBwcFKSkrS5cuXdeDAAW3dulU7d+50+gE7SUlJ6tmzp06fPi3p3+Ney5Yt1aFDB5UtW1b58uXT2bNntXz5ctM1pYsXL2rUqFFasmSJDh48qD59+qRd1y1QoIA6duyoVq1aqWTJkkpJSdHx48c1b9487d+/36KczZs366OPPtLo0aPtbnOnTp1sXpcrU6aMHnzwQdWoUUPFihXTxYsXtXPnTv32229pD1z9+++/9eKLLzr8XQEAAAAAkOO4fW5yAAAAAADgFU6ePGlIsni1bt3a082yW/fu3U3tf/bZZ+3O37p1a1P+kydPZl+DXSg8PNzU9qFDh2ZrfSVLljT++9//Gps3bzZSUlIyzZOammosXbrUqFq1qqmtc+fOtbtu67xjx47NwicxjO+++85UZrFixYypU6caN2/ezPDzzJ8/3wgJCTHlX7x4cab1Dh061CJP3rx5DR8fH0OSERQUZHz99ddGcnKyzbwJCQnGK6+8YqrXz8/POHv2rF2f++jRo0aRIkVMZYSGhhqTJ082kpKSMswfHx9vLFy40OjSpYtRoUKFdNd7+umnLcr38fExjh49alcbb/fhhx+a2rpkyRKHy3GE9TaSZISHhztUxokTJ4zatWubyhk4cKDdZVj3TX5+fmn/L168uPH9998bqampNvOmpqYa8fHxFmmrVq0yfH19LcosUKCA8e677xpXr17NsC3h4eFG5cqVTZ/niy++sOuzBAQEGEOHDjWWL19u3Lhxw648+/btMzp06GCq86mnnrIrv2EYRvny5R3qH9etW2cUL17cVOeTTz6Z7u/S2vTp0035fXx8jJdeeindz56UlGS8+eabRp48eSy2jTPH5SeeeMJmH/Haa6+l27clJycbH3zwgZEvXz5T3l69emVaZ/Xq1S3yPPTQQ5nmefXVV03f0e3L+/btyzB/XFycxfclyXj77bczzGP9m8qfP3/a/0uWLGnMmzcv3bzXrl0zhgwZYvp+ihQpYvc+nRW2jve3t//ee+81Dh06lG7+ZcuWGWXKlDGVUb16dVNfYe1O78+vX79uBAcHm8r56KOPnG5DzZo1jRUrVqTbhxuGYdy4ccN49913Tft50aJFjX/++SfdfDdv3jQCAwMt8gQEBBjfffedXeO2+Ph4Y8WKFcbDDz9stGrVKtP1jx49aqpPklG7dm1j8+bN6eY7cOCA0axZM1O+PHnyGFu3bs20Xlt9rbPjd+ty7Bljjh071mZfe+vf//3vf0ZcXFy6+a37Y3eNz24ZM2aMqa677rrLmDNnTobHu6SkJOObb74xbfO8efMa27dvz7Te7Gbr9zZ9+vQM85w/f970Oxs8eLDDdcfHx5v6isaNG2eYx9Z+fHvf3rVrVyMiIiLd/DNnzrS537Rt2zbD/uV27u6jchLrcYO9Y7GMtmnTpk0z/K2cPHnSaNiwoamMTp062VW3p/cpR8fe6bHVx9rDVfW7kzPHoKzks/WbL1y4sPHtt9+mmycyMtJ4+OGH09a3Pk9xpH5vOS+8/dy6QoUKGY5Jk5OTMz0Ou9qsWbNMn7dhw4aZniPdcv78eWPq1KlGgwYNjMmTJ2e6/oYNG4y8efOa6qxUqZLx888/Z/r7j42NNX788Ufjvvvuy7SvPHnypFGkSBHj6aefNlavXm0kJiba9ZnWr19vNG7c2NTGiRMn2pXfMDzbP+c0nriuYBi56zjiyXN4w3B+HGPN2fMuV9XvTra2maPXD5wtw9l8kZGRNv9G0aRJE2P37t3p5jtx4oTRvn37DI/t9tTv6etszo5HPGnixImmdksywsLCjC1btmSa/+zZs8bHH39sVKpUKdPPa92n3d4/N2jQwNi2bVu6eZcvX24ULFjQ1M6///7baNCgQdpy//79jXPnztksIyUlxXjrrbdMZRQuXNjubWyrP8+XL5/x3nvvpXvtIi4uznjuuefS1vfx8TEdm3LCeQIAAAAAAI4gKBwAAAAAgDtUTg4K/+uvv0xt9/HxyfCmF2sEhdvv+vXrTt8Me/nyZYsbRm7dAGcvV97kc/LkSSMgIMCivLvvvtuhAIYzZ84Yd911l0UZtWrVyvRmWVs3YUv/BqTv2rXLrrofe+wxU/4333zTrrxNmzY15a1Vq5Zx5swZu/LfLqPfycGDB031vPTSSw6Vn5qaalSpUsWijPLly9sV1JYVjgYRpqamGnFxccaJEyeMhQsXGiNGjLB5M13t2rWN6Ohou9thq2+S/g0Q279/v0OfKTY21ggNDbUoJyQkxNizZ4/dZcTExBh169a1KCM4ONi4fv26XXmdkZKSYgwfPtyizoIFCxqXL1+2K78jN/TOmTPH4ubFW8cTR24yj4mJMYoWLWraZp9//rld+efOnWsRoODocXndunWmfL6+vsb3339vV/1LliwxBXdJyvAmTsMwBw0XL148099pkyZNLPL06dPHYvmTTz7JMP+yZctM7cwoANUw0v9NVapUyTh16lSGeQ3j3996p06dTPlnzZqVad6ssnW8v/UKCwvL8GEmtxw/ftwoXbq0Kf+ECRMyzHcn9ee2vP7666Yy/P39073p9Xa//PKLKW/Pnj2NhIQEu+v/448/TL/LUaNGpbv+kiVLTHXOmDHD7vpuZ0//bitIq3Hjxnb1+zdv3jTatm1ryl+nTp1M83pjUPitPnfOnDkOt8Fd4zPD+Dfwy/ohMffee69Dx+pdu3YZhQoVsiijc+fODrfV1ZwJCjcMw+jfv79Fnvz58xtRUVEO1W0rgC+jIEvDsL0f33oNGDDArj5yy5YtRlBQkCm/Pcd+T/RROYmrgsJvvbp162bX8To6Oto0bvf19TVOnz6daV5P71O5KZjPXZw5Bjmbb82aNaZ8gYGBxsaNG+2q89lnn013/7K33d5yXnjrVa1atQwflOAp1udGwcHBDh+XbslsPJeQkGCUK1fO9N20bt3auHLlisP1ZTYOSUhIcPqhWjdv3jTuv/9+i3aWLVvW7uuUnuyfcxJPXVcwjNx1HPHkObxhEBTujJwYFD5y5EhTvpYtW9p1Lp+UlGT07t073f3UmaDwWy93XWdzdjziKXv37rV53fc///mPw9fHkpOTM71ekN74p1WrVsa1a9cyrePHH3805b39IQQvv/yyXW0dMWKEqZzZs2dnmu/YsWOm44m/v7+xYMECu+r96KOP0t2/c8J5AgAAAAAAjvAVAAAAAADA/7dt2zbVr18/y6/Dhw9nWxuvXr2q4cOHm9IHDhyounXrZqnsLl26ZPmzT5w4MUtt8EYBAQHy9/d3Km/RokX1/fffW6Rt3LhRBw4ccEXTHDJx4kTduHEjbblgwYJavny57rrrLrvLKFu2rH7++WeLtP3792vx4sVOtWn69OmqV6+eXeu+9957yp8/v0XaH3/8kWm+FStWaPPmzRZpwcHBWrlypcqWLWt/Y/+/ChUqpPte9erV1a5dO4u06dOnKyEhwe7yV61apWPHjlmkPfHEE/L1df+lzDZt2sjHx8fmy9fXV4GBgapUqZIeeOABTZs2TTdv3kzL6+vrq0GDBmnNmjUqVqxYltsybdo01axZ06E8U6ZM0cWLFy3atHDhQtWpU8fuMgoXLqwFCxYob968aWlRUVGaNm2aXXmd4evrqy+//NJi/7x+/bp++uknp8pLz8SJE9WvXz/Fx8enpeXPn19z5szRSy+9ZHc533//va5cuWKRNnjwYD399NN25e/Tp49Gjx5td33WPv74Y1Paf/7zHw0ePNiu/F27dtWbb75pSp80aVKG+dq3b2+xHB0drZ07d6a7fkxMjLZv3562XKZMGT3zzDMW66xcuTLDOletWmWxXKRIETVq1CjDPLbkyZNHc+bMUfny5TNd18fHRx999JEp3Z7+N7sUL15c8+bNMx0TbKlUqZJmz55tSv/qq6+UlJSUbr7c1p/byzAMffjhh3rnnXdM7z355JMqVapUpvknTJhgkVavXj3NmTPHoh/NTMeOHTV27FiLtOnTp+vSpUs21z9x4oTFcoECBTRw4EC767tdQEBAhu/v27fP9FstVKiQfvvtN7v6/fz582v+/PkqWbKkRfrevXu1YsUKxxvsBZ5//nk99NBDDuVx5/hMkt566y2lpqamLZcuXVrLli1z6Fhdr149ffXVVxZpv//+u3bv3u1QW73FU089ZbEcHx+v6dOnO1TG5MmTLZaLFCmi/v37O9Weu+++W9OnT7erj2zSpIk+//xzU/qnn36aYT5P9VF3qgoVKuiHH36w63hdrFgx03eampqa6dgoI+7Yp+D9bG3DTz/9VM2aNbMr/yeffKLmzZtnqQ3edF7o7++vn376SaVLl3a6jOxiPZ7r1auXihcv7lRZmY3nZsyYoTNnzlik3X333Vq6dKmKFCnicH2ZjUPy5s2rAgUKOFyu9O/YcebMmRaf6Z9//snSuNHT/bM38tR1hTuFO87hcWeIjY3VrFmzLNIKFy6sOXPmZNr3S/8eB7///nuVK1fOpe3K6dfZstM777yjlJQUi7QBAwbo448/dvj6mJ+fn1PXC4oXL66ff/5ZgYGBma778MMPm/4Gces8r3Xr1nrvvffsqnP8+PGmz/f7779nms9WX/fqq6+qZ8+edtX7/PPP6+GHH7ZrXQAAAAAAcjrvvfMGAAAAAAC43fXr17V79+4sv24PjHQlwzA0ZMgQnTp1yiI9ODhYH374YZbLP3jwYJY/e0RERJbbkdvUrl1bDRs2tEhbt26dW9sQGRlpCvJ4+eWXVbFiRYfLuu+++0yBcgsWLHC4nNatW6tHjx52r1+sWDF16dLFIm3Xrl0WAT62vP/++6a0zz//PNPANmdZB8JGR0drzpw5due3Dq7JkyePHn30UZe0zR2CgoL02muv6ejRo5o1a5ZLAsLbtGmjbt26OZQnMTFRn3zyiUXakCFD7L75/3aVKlUy3QjszD7viPz585sC7FzVb6SkpGjUqFEaPXq0DMNISw8ODtaff/6pPn36OFTelClTLJbz58/v8ANC3njjDVOApD0iIiL022+/WaSFhISYAr4y88ILL6hq1aoWaRs3btSOHTvSzRMWFiY/Pz+LNOug7dv99ddfFv1V+/btde+996pgwYJpaX///beSk5PTLcO6fFttsMeAAQMcCiavWbOm6Th2e4C7u40bN86hAJGwsDA9+OCDFmkXLlzQwoULM8x3J/TnqampiomJ0e7du/XFF1+oQYMGevnlly36Bklq2LChzUBxa0uXLtX+/fst0j799FPlyZPH4ba98MILCgoKSluOj49P9wbaa9euWSwXLlzY6Qf6ZOaLL74wpb3xxhsqU6aM3WUULlzY5o3Etsr2dkFBQRo3bpzD+dw5Ptu3b5+WLVtmkfbOO+84FfQ1YMAA0/HC+jiUU7Ro0UL169e3SJs6darp95+ePXv2aMOGDRZpQ4YMsSsYw5ZJkyY5FJg9ZMgQNW7c2CJt+/bt2rZtW7p5PNVH3anGjh3rUDBs//79TeOarIw33LFPwbudP39eixYtskhr2LChHnnkEbvL8PHxsfnAAHdx9Xnh4MGD1aBBg6w2K1tYj+ecDQi3xwcffGBKmzlzpsW5mTcJCQnR/fffb5GWlf3A0/2zt/HkdYU7hbvO4ZH7zZ49W9evX7dI++9//+vQNcWCBQvadX3DETn9Olt2OXXqlOk6WokSJUzXy7Lb888/79C1Buv+55Z33nnH7kD20qVLmx4slNnxICEhQTNmzDCV8+qrr9pV5y2TJk1Svnz5HMoDAAAAAEBORFA4AAAAAADIMV599VXTDa0+Pj767rvvFBoa6qFWwR7WNwVu2rTJrfUvXbrU9LCCESNGOF1e165dLZZXr17tcBmPPfaYw3nuuecei+W4uLgMH0QQGxurNWvWWKRVqFDB4dksHdG9e3fTrCDWQbPpOXfunGnW9d69eyskJMRl7ctu165d0/vvv6+RI0e6bOYoZ4IoN2zYoHPnzlmkuXKf37Rpk0MzBjsjO/qNuLg49ejRw7RPVqlSRRs3bnR4FrwzZ87owIEDFmk9evRw+JgUEBCgQYMGOZRH+jfQ2nq2mSFDhjh8M3+ePHls9kkZ7cOFCxc2BQ5lFBRu/V779u2VJ08etW7dOi3t2rVr6W7nS5cuae/evaYynOGK/vfIkSNO1Z1V+fPnt3u2tts9/vjjprTMgvdyU3/epk0b+fj4mF5+fn4qWrSo6tevr2eeecbmjMdt27bVihUr7PpdzZs3z2K5atWqFvu4IwoUKKA2bdpYpKU33rAOMLh48aJplnZXse4X8uXL59Rxqn///qYHp4SHh5v6NG/Xr18/u2bbup27x2fW+2VQUJD69evnVFk+Pj7q3LmzRZoz42BvYT1b+LFjxzI8lt3OVn84cuRIp9pRpkwZ08OfMuPj42PzeJZR3+6pPupOVLBgQQ0YMMChPEWLFjWNfw8fPuxU/e7ap+DdVq5caXrg0ogRI+Tj4+NQOQ0bNjSN+93JleeF3vaAottZj+ey62GK+/fv1/Hjxy3SWrZs6dQD5NzJVfuBp/tnb+TJ6wp3AneewyP3++uvvyyW/fz8NHToUIfLefDBB516SFh6cvJ1tuy0dOlSU/86cuRIFSpUyK3tcHT8Y+sBOtWrV3f4url1OZlt482bN+vy5csWaYMGDVKBAgUcqrdUqVLq3r27Q3kAAAAAAMiJsmeaAAAAAAAAABf76quvbM6o99prr/EHfg84fvy4Nm3apD179uj48eOKjY1VbGysEhISbM6ud+bMmQyXs5t14E358uUdmtHSmvUM46dOnVJMTIxDN1M5E4BRuXJlU9rVq1dVtmxZm+uvXbvWdOPRgAEDnJpZ115+fn4aOXKkxQwOGzZs0J49e1S3bt0M837zzTemm9ZHjRqVLe20R+XKlTMM9EpOTtbVq1d18eJFJSUlpaWnpKRo5cqVWrlypfr376+pU6dm6WYv64Abe1jv83ny5FGTJk2cboP1Ph8fH6+DBw+aZtjMSHR0tNauXau9e/fq4MGDunLliq5du6br16/b7DesbwL7559/nGr7LefOnVO3bt20c+dOi/TmzZtr4cKFCg4OdrhMWzei9+7d26n29e7dWx9++KFDedavX29Kc3Sm81v69u2r0aNHZ1r+7dq3b6/NmzdbrJ+QkGBzNhZbQeG3/r19BtuVK1eqRYsWpvx//fWXaT9xJii8QIECphtP7WHd/6akpCguLs7hYNCsCgsLc2hWu1vat2+vQoUKKTY2Ni0ts0CK3NSfO6N+/fp66aWXNGDAALuDp6z7XkdvmLVm3fda91+3NG3a1GLZMAz1799fCxYsSHeM4IwLFy7oxIkTFmlt2rQxBXfbI1++fOrRo4fFLFBxcXHavXu3acYwb+bMMdrd4zPr/bJhw4bKnz+/0+XZu1/mBAMHDtTo0aN15cqVtLTJkyerQ4cOGeaLi4vTDz/8YJEWFhamGjVqONWO7t272z3j2u169+6tJ554wiIto77dU33UnahZs2YOzdJ9S+XKlXXo0KG05atXrzpVv7v2KXg3V5+ruGrWeE+dFxYoUMCrA5+bNm1qsc3WrVun119/XePHj5e/v+tu7bL1AA9nAlazKiIiIu3c4siRI7p69apiY2N18+ZNm/vBhQsXLJadva7o6f7ZG3n6ukJu585zeOR+1vtAgwYNHJoB+pb8+fOrXbt2+vXXX7Pcppx+nS07ecMxt2rVqg7NJC/J9IBI6d8HyDiqQoUKFsvJyckZbmNXj12tH4oGAAAAAEBuQ1A4AAAAAABI07p1a6+c3Wv27Nl65plnTOlDhw7Vm2++6bJ6Tp48abpRAf8nNTVV3377rb755htt3bo1S2XFxMS4plF2sr4BMSoqyqFgVmtxcXGmtKioKLuDwvPnz6+77rrL4Xpt3USY0Y2oGzduNKXdd999DtfrqBEjRmj8+PGKj49PS5s8ebImT56cbp6UlBR98803Fmk1a9Z0evZCV5g2bZrCwsIyXS8xMVF79uzRL7/8oqlTp+ratWtp7/388886efKkVqxY4VRgeGhoqEqXLu1wPls33Tpzg94tiYmJprSoqCi78v7555/65JNP9Mcff1gEzzsqsxvHMrJ371517drVFEDQp08fzZo1y+nguO3bt5vSGjVq5FRZ9evXl5+fn0Oz5O7YscNiOU+ePKpXr55T9ZcvX14lSpRQZGRkuuVba9++vd5+++205Zs3b2rdunVq166dxXpnzpzR0aNH05Zr166ddkOidWD3qlWrNH78eFNd1kHlZcuWVbVq1TL5VGbly5dXnjx5HM6XXv/r7ptVnd2/fH19Va9ePa1duzYt7eDBg7px44YCAgLSzZdb+nNHFSpUSAMGDFDfvn3tDgg/d+6cTp06ZZG2fPnyLI03rINf0ut369evrwYNGlgEZG7fvl133323+vbtq759+6pt27YOz65kzVafkJWZQ5s0aWIRFH6rjpwUFO5MW905PktJSTHdWL1nz54s7ZfWwXlXr15VUlKSU32rpxUoUEDDhw/XpEmT0tIWL16siIiIDB8g9cMPP1iM96SsPfjC2b49ODhYZcuWtRjf2BqbSJ7to+5E1jPK2st6vOFs0KE79il4P+ttV6ZMGYWGhjpVlrP71O08fV5Yt27dbH1AXlYNGzZMn332mUVA9DvvvKMff/xRjzzyiHr16qU6depkuR5PXSe6Zd68efrqq6+0Zs0apaamOl2Os9cVPd0/eyNPX1fI7dx9Do/cKyYmRmfPnrVIy8q5c4MGDVwSFJ7Tr7NlJ+tjbokSJZw+DjmrSpUqDucJCgrKtnIy2sbWY1d/f3+nj0euGLsCAAAAAODtCAoHAAAAAABebf78+Ro2bJjpRsE+ffro22+/tTtQB1lz8OBBDRw40GWzv7n75knrG6auX7+u3bt3u7SO6Ohou2+OcWZGTUk2b7DK6GbqixcvmtJccRNxZoKDg9WvXz/NnDkzLe2HH37QBx98YPNmIElatGiRIiIiLNJGjhyZre10lbx586px48Zq3Lixnn32WfXo0UO7du1Ke3/z5s168sknTTNK2iMkJMSpNlnv80lJSdmyz2ckNjZWjz32mObMmeOyOp25OXDHjh1q0aKFxexKkvTiiy9q4sSJWTqOXLp0yWLZ39/fNNONvQoUKKBy5crp5MmTduexDr6qUKFClmZ/rVmzpsUsopkFdzVv3lwBAQG6ceNGWtqqVatMQeHpzRIu/dsnhYaGpvVXW7ZsUWxsrOkhCn/++afFsnUd9nJX/5tdnAmEv6V69eoWN5QbhqGoqCiVK1cu3Ty5pT+vXLmyqe8wDEPXr1/XuXPndPPmTYv3YmNjNXr0aC1evFiLFy+2a2Y3635X+vc4bOtY7KyM+t2vvvpKYWFhSkhISEuLj4/X999/r++//1558+ZVkyZN1KxZMzVt2lStWrVyODDMVp/g7MzI0r99jj11eDNnjtPuHJ9FR0dbPNRBkq5cuWIxM7YrXL582elAQ0978skn9fHHH6edbyYnJ+ubb77RuHHj0s0zZcoUi+XQ0FD16tXL6TZktW+/PYA3KipKhmGYxjee7qPuNK4abzg71nDHPgXvZ32uktX9wlnecl7o7Lm1u9SvX1/PPvusPv30U4v0U6dOaezYsRo7dqxCQkLUokULNWnSRM2bN1fTpk2VL18+h+qx7vf9/f2zNJ6z17lz5zR48GD99ddfLinP2euK7uifFy1apDFjxjhUfuPGjTVt2jSn2pZVnr6ukNu5+xweuZetsXZWHnBcsWLFLLTm/+T062zZyXos5o6/y1grWrSow3lsbRtXlZPRNrb+vsqVK+f08ahq1aoOP3wVAAAAAICcxtfTDQAAAAAAAEjPkiVL1L9/fyUnJ1uk9+jRQz/++KNXz/CTm+zbt0+tW7d2WUC45N4bfG7evGkK9squeuzlrpkUrWdylJy7gccZTz31lMVyXFycZs+ene761sE1AQEBGjJkSLa0LTuVLVtWv//+uymAcPbs2fr7778dLs+Z2cUl9wTlZLTPx8bGqlOnTi698V9yru/Yu3evKSD8P//5jz788MMsB7dYz04WFBSUpTLtCTy9nXVQX5EiRZyuWzL3DwkJCRYB39by5s2rli1bWqStXLnStJ51UHiHDh0slm8P8E5OTtbq1ast3j927JhpdlPrGcbtlRNnsr2do/tIZnntmWEvN/Tn06ZN065duyxeu3fv1rFjx3Tt2jVt27ZNo0aNkr+/5bOU165dq27duikxMTHTOtzR71oH996uWbNmWrJkiYKDg22+n5iYqPXr12vSpEnq27evSpYsqZo1a2rMmDE6fPiwXfXbCiTOSr9ja0xia+zizZw5TrtzfOauIF13jLWzS6VKlXT//fdbpE2bNi3dm8c3btxoetDOiBEjsnR8cWXfnpKSYprFXPJ8H3Wn8fR4wx37FLyf9TjP1eNIe3jTeaGz59buNGnSJL3wwgvpvn/p0iXNnz9fr776qlq3bq0iRYqoU6dOmj59ut2/U+txSOHChbP9oQ8RERFq3bq1ywLCJZmuFdvLHf3z5cuXtXv3bodex44dy/Z2pcfT1xVyO0+cwyN3snU+7oljuzVPj3u91bVr10zjFXf9XeZ2rto+7tjOrhy7+vj4pPswSwAAAAAAcguCwgEAAAAAgFf6448/1KdPH9ONE507d9bcuXO52cRNkpKS1LdvX0VGRprea9GihcaNG6clS5Zo9+7dunTpkq5du6bk5GQZhmHxGjp0qAda/y9Xz4SYk1gHwkpSwYIF3VJ3kyZNdM8991ikTZ482ea6x44dMwWSDhgwwGU3p7lbyZIl9fTTT5vSP/vsM4fLsg5QtJen9/sXXnhBmzZtMqVXrVpVzz//vObMmaMtW7bo3Llzunr1qhISEkz9xvTp013SFlvf4Xfffad169ZluWzrG++z+vtyNL876s8suMA6OHvnzp0WgQaGYVjc/J8nTx61bt06wzKsg8itlyXnZwrP6bKyjZ3ZvlLu78/9/PzUqFEjffXVV/rzzz9NbV23bp1efvnlTMvxdL8r/ftbOnz4sF599dV0g8Nvd/DgQb355puqUaOG+vTpo5MnT2a4vq39xRP7pDdx5jjtzvGZN+yXOYH1uC0iIkKLFi2yua51/+fr66vHH388S/W743fEvnBnudP7ZvzLlecKzub19vNCb+Pn56dJkyZpy5Yt6t69e6Ztjo+P14oVKzR8+HBVqFBB7777bqbB0tbjEEdnXHfGsGHDbAY9169fX6+++qoWLFigHTt26MKFC4qNjVViYqJpPxg7dmy2t/NO5Q3XFXIzjslwlYSEBFNa3rx5nS4vX758WWkOMmHrvN8dx9yczNPX2QEAAAAAyGkICgcAAAAAAF5n1apV6tmzp+lGlw4dOmj+/PlZutkFjvn666918OBBi7TKlStr69atWrt2rcaOHauuXbuqbt26KlGihAIDA23O4O7J2QMLFChgSmvatKnpBtOsvsLCwtz/4TJhayas69evu61+6wCbPXv2aMOGDab1pk6dKsMwLNJGjhyZrW3Lbt26dTOlrVq1SqmpqW6p33q/Dw0Ndfk+P2zYMJt17927V999951FWmBgoH744QcdPnxYH330kR566CE1adJEpUqVUqFChWz2667qN/r3769BgwZZpN2asW7FihVZKtt6xpGs/r4cze+O+jObVcU6ODs1NdUiCHzv3r26ePFi2nKzZs1MN+VZzxxuHVT8559/WizXqlVLJUuWzLBduVVWtrEz2/eWO6U/b9WqlebOnStfX8s/n33++edas2ZNhnltjTdeeeUVl/e9mSlWrJjeeecdnT9/XsuXL9dLL72ke+65J8Pxs2EY+vXXX1W/fn398ccf6a5na3/x1D6Zk7lzfGZrv+zXr5/L98sKFSpkS/vd5f7771eVKlUs0mw9/CI6Olpz5861SOvSpYvKlSuXpfrd8Tvylj4K7kHfDMm15wrO5PW288KcpEmTJlq0aJEiIiL07bffatCgQapYsWKGeS5fvqzXXntNLVq0yHAmYetxSFxcnCuanK6lS5eaHvIVEhKiP/74Qzt37tQ777yjnj17qkGDBgoNDVVQUJDNB4HeifuBu3jDdYXcjGMyXMXWw/ay8pAAW0HLcB1b5/3ZfczN6Tx9nR0AAAAAgJyGoHAAAAAAAOBVwsPD1aNHD8XHx1ukt23bVgsXLlT+/Pk91LI7008//WSxHBQUpFWrVqlx48YOlXP7rLHuVqRIEdPsSp5sjzsVL17clObOWQL79u2rEiVKWKRZB9gkJCSYZv5q0qSJGjVqlO3ty05Vq1Y1pV29elWnTp1yS/3WM8S6c7v/8ssvpqCgmTNnauDAgfLx8bG7HFf9Tv38/PT999+bAlNv3LihHj166LfffnO67CJFilgsX7t2LUsBUVevXnVo/aJFi1osZ3Tzvz2s8+fLl08BAQEZ5qlfv75pf7v9pn/rAADrAHBJuuuuu1StWrW05UOHDikiIkLSv0Hm4eHhFutbzyx+J3F0H8ksr/U+nJ47qT/v0KGD/vOf/1ikGYahp59+WikpKenmszUztyfHG/7+/urUqZMmTpyozZs3KzY2VmvXrtW7776rsLAwmzNPxsbG6sEHH9SRI0dslmnd50hZ63ds5S1WrJjT5dkrKSkp2+vIiDvHZ962X3orHx8fPfnkkxZpq1atMs1qOn36dNN56qhRo7Jcvyv7dj8/P5vBQuwLdxZ37FOu5um+OTeyHue5ehyZGW87L8yJQkJCNHz4cM2aNUsnTpzQhQsXNG/ePD377LM2rzlI0ubNm9W3b990y7Qeh1y9ejVbH+phfV3Rz89PixcvVseOHR0qJyftB8OGDXP4oSqrV6/2WHu94bqCK3jrccRT5/BZ4a3f5Z3O1vl4dHS00+VlJS8yZ+shJ+68Pp8TuXLsahhGlh6aAAAAAABATkBQOAAAAAAA8Bpr1qxRt27dTLO/tG7dWosXL7Y5uxmyT1xcnDZu3GiRNmTIEKdmAjxx4oSLWuU4Hx8fUyBbRESEkpOTPdQi97E1k+6ePXvcVn++fPn02GOPWaTNmzfP4qazuXPnmm5Cc0VwjafZmg1EkqKiotxSf2hoqMVyYmKizp8/75a6rWd5rlWrlnr37u1wOa7sN3x8fDR58mS99NJLFukJCQl66KGH9OOPPzpVbkhIiMVycnKyjh8/7lRZN2/e1JkzZxzKY923nTx5UgkJCU7VL0kHDhywWLYVQGbNx8dHbdu2tUjLKCg8vYBu6/Rb+Xbu3GnqI+7koPD0gnXtcfjwYYtlHx8fu7axdOf152+++aZKly5tkbZv3z7NnDkz3TzW/a4knT592uVtc1a+fPnUokUL/fe//1V4eLguXLig999/33TT7fXr1/W///3PZhnWfY4kHTx40Ok2Wfc5Usb9jq1ZI50JWPD0ze/uHJ+VKFHCFHjnTfulN3nkkUcsApYMw9DUqVPTXZakChUq6P77789y3a7s24ODg20GW3p7HwXXcsc+dYt13+xsIJmn++bcyPpcxXrbOuLQoUMO5/HG88KcLjQ0VA8++KA+/fRTHTlyRNu3b1f//v1N661cuVK///67zTKsxyHJyck2x2SuYr0f3H///brnnnscLof9IPt4+rpCbj+OuPMcPrd/l3e6kJAQ5cuXzyJt7969Tpfnzr8R3Kmsj7lZ2V53Auux65kzZ0wPZbPX0aNHM3ywIwAAAAAAuQFB4QAAAAAAwCusXbtWXbt21Y0bNyzSW7ZsqaVLl7plRhFYOnfunFJTUy3SWrZs6XA5Fy9e9PjNm02bNrVYvnHjhrZv3+6h1rjPvffea0pbv369W9swcuRI+fn5pS3Hx8dbzCRrPdNs0aJFbd7UnNOkN5PF7d9FdrLe5yXp77//dkvd//zzj8WyM/2GJNNDKVxh4sSJGj9+vEVacnKyBg8erG+++cbh8mzNgOxs37Jr1y6Hb1Zr2LChxXJycrJ27drlVP1nzpzRpUuXLNLsneHZOkj7+PHjOnXqlJKSkiz2u0KFCqUbAGBdxq3gAeugcn9/f7Vu3dquduVGzu5fqamppn2jRo0aDo2v7qT+PCAgQBMmTDCljx8/XomJiTbzVKlSxTTL9YYNG7z2JtTixYtr9OjR2rRpk2kG2CVLltgMBLHucyRp27ZtTrdh69atprSM+h1bD1yJjY11uF7r2Z/dzZ3js/z586tevXoWaUeOHNHFixezpb6crEiRIho4cKBF2vTp09N+C7ZmDn/iiSfk65v1P7c727dHRUWZHiiT3m8op/VRyBp37FO3WPfNzvTLkuf75tzIettFREQ43f87s09583lhbtGwYUP99NNPevvtt03v/frrrzbzuHMckpCQYDrHdGY/SElJ0ZYtW1zVLFjx9HWF3H4ccec5fG7/Lu90efLkUf369S3StmzZYvr7jb02bdrkglYhI9bH3MjIyCw9KCK3sz5eJCcna/fu3U6VdSf87Q8AAAAAAILCAQAAAACAx23YsEFdunTR9evXLdLvu+8+LVu2TAULFvRQy+5stmY0tg4ksMecOXOcboN1AK2zQQsdOnQwpc2fP9+psnKSFi1ayN/f3yLtp59+cmvwR9myZdWjRw+LtKlTp8owDO3Zs0cbNmyweG/o0KEqUKCA29qXXdKbSc3W7KDZwZP7vHXf4Uy/sXfv3izNPpuRMWPG6KOPPrJIS01N1eOPP66PP/7YobKaNWtmSluwYIFT7XJm+zRv3tyUNm/ePKfqnzt3rl3l22Jr5u6VK1dq48aNFsf2Nm3apPtgBOv3/vzzT0nmoPCmTZuaAljvJOHh4ek+dCIjq1atMt0Qbmv/zcid1p8PHTpUVapUsUg7c+aMpk2bZnN9X19ftWvXziItLi5OK1asyLY2ukK1atX06KOPWqTduHFDx48fN60bGhqqSpUqWaSFh4fr8uXLDtebmJioRYsWWaQFBgaqbt266eaxntVccm7WyDVr1jicx5XcPT67U8fBznj66actlqOjo9POZawffJE3b14NHz7cJfUuWrTIqWAOW9sxvb49p/ZRcI479qlbrPtmZ/rlxMREpwOTrPtTHnTwfzx9ruLt54W5ySuvvKLixYtbpKU3A2xYWJgpbdasWdnRLJuzDTuzHyxbtkxxcXGuaBJs8PR1hdx+HHHnObz1d3nq1CkZhuFw3c6eL3FMzn7WQcYXLlxQeHi4w+UcOXIkSw948yRX/b3IHdx5zM0NPD12BQAAAAAgpyEoHAAAAAAAeNTmzZvVuXNn08199957r37//XcFBgZ6qGWwFYxvK1A8I0lJSfr888+dboN14J+zN4F27drVdMPQlClTFBMT42zTcoSgoCBT8MepU6eyFKjvDOsAm2PHjmnVqlWaMmWKad2RI0e6q1nZasmSJaa0IkWKuC0ovHXr1ipcuLBF2q+//qqjR49me93WfYej/YYkU9C2qz3//PP6+uuvTbN7vvDCC3rzzTftLqdcuXKqWbOmRdrChQtNM2Nl5ubNm/rhhx8cyiNJ7dq1M/Vts2bNMj1kJTPJyck2Z0rv2LGjXfkrVqxoChRdtWqVKaDbVvD4LYULF1bjxo3Tli9cuKBt27aZZq3LqIw7QXx8vFP7iq3t27lzZ4fLuZP6c39/f40ZM8aU/s4779icRVuSHnjgAVPau+++6/K2uVr16tVNaekFLnTq1MliOSEhwWLGeHv98ssvpkChtm3bpvvgCOnfAHZrjs4amZKSom+//dahPK7m7vGZrf3yww8/VHJycrbUl5PVrVvXNIPplClTdO7cOS1evNgi/cEHH1RISIhL6o2IiNDvv//ucD5b+3JGfXtO7aPgOHftU5K5bz5y5IjDwW+zZ892ePx6i6uuGeRGHTp0MAXoTZs2zeEAwV27djkVOJYTzgtzCz8/P1WtWtUiLb3fYY0aNUy/23Xr1mXLjOyuuK4osR9kN09fV8jtxxF3nsNbf5dxcXE6cOCAQ/WGh4c7PVM4x+Ts169fP1Pahx9+6HA5EydOdEVzPCIn7WfdunUzjcWmTp1qeuAD/tW0aVPTw2NmzZql+Ph4h8q5cOGC6fwdAAAAAIDciKBwAAAAAADgMdu3b1enTp1MN0Hcc889Wr58+R09E6g3KFWqlCnN0Znkxo8fn6Ug1KJFi1osOzNbjCSVL19egwcPtkiLjY3VI4884tSMKTnJK6+8Ykp79tlndf78ebe1oW3btqbA2YkTJ5puimzbtq3NgK+cJiIiQl999ZUp3dbDCbJLwYIF9fzzz1ukpaSkaNCgQekGM7qKdd+xatUqh2YqXLVqlWbOnOnqZpk89thj+uGHH0w3540ZM8bm7yY91oGv8fHxGj16tENtefvtt3XhwgWH8khS6dKl1atXL4u0ixcvavz48Q6V88knn+jw4cMWaffdd58aNGhgdxnWwdp//fWXVq5cmeE61qxnsx0/frxu3rzpUBl3gnHjxunKlSt2r//333+bZnorWbKkzeDAzNxp/fmAAQNMnyMiIkJTp061uX6/fv1Ms4uvXbtWH3/8cba10RVsjQlKlChhc90nn3zSlPbmm286NK6IjY212c8+88wzGeYLCQnRXXfdZZE2Z84ch2YG+/LLL3Xy5Em7188u7hyf3XfffaYZyk6cOKEXX3zR5XXlBtYPv9iwYYOeffZZUxD9qFGjXFrvSy+9pKSkJLvXnzVrlumhCI0aNbJ4wIq1nNpHwTnu2KdurXO75ORkhx5ycfXqVYceymTNVdcMcqNSpUqpR48eFmnbt2936FzLMIxMj88Z1X87bz0vzC2sxxDpjeUk2+OQYcOGOR1Um57ChQsrICDAIs3R64rTpk3T6tWrXdgqWPP0dYU74TjirnN46+9Skn788Ue7601KStJ///tfu9e3Zv1dnjx5Mtdfd3e3Zs2amX5Ty5cvd+jBA3/99ZfHH5SWFTlp7Fe2bFkNGDDAIi0yMtLl55K5Rb58+TRs2DCLtHPnzum9995zqJyXXnop2//+AQAAAACANyAoHAAAAAAAeMTu3bvVsWNH08wfjRs31ooVK1SoUCEPtQy3hISE6O6777ZImz17tnbv3m1X/unTp2d55rk6depYLK9Zs8bpm1THjBmjfPnyWaT99ttvevzxx52+SeTUqVN65plntG/fPqfyu0ObNm1MMx5GRUWpY8eOOnv2rMPlnTp1yql2PPXUUxbLK1eu1LVr1yzScvqsspJ0+vRpde7c2fTZJOnxxx93a1uef/55BQcHW6Rt2bJFffr0cXjWpVsuXbqkN954wxTsezvr/e3EiRM2ZxG2ZceOHXr44YfddtPoww8/rHnz5pn6hg8++EBPPfWUXe0YMmSIihQpYpE2c+ZMuz/zggUL9P7779vdZmvWwf+SNGnSJP3888925V++fLlef/11U7qjwYLWs95GRUVp06ZNact33XWXzdmIb2cd8L1kyRKL5cDAQDVt2tShduVGUVFReuihh+w6dp06dUoDBw40pY8aNUp58uRxqv47pT+X/p110dZs4e+9957pgQXSv7OL2wqeGD16dLqB5PbYsGGD6Ubi23388ccZ9ssZiY2N1YwZMyzSihQpovLly9tcv3bt2qbZ/q5evapevXrZNUNXQkKC+vTpYwpcqlu3rl0PfbCeHe/MmTP65JNPMs0nSX/++afDD+3ILu4en7311lvy8fGxSPvss880duxYp4+5+/bt05AhQxwKcMkJevfurdKlS1uk/frrrxbLtWrVMm2/rDp06JBGjBhh1/bYsWOHKXhd+vfBAhnxVB8Fz3DHPiX9OwOsr6/lbScTJkyw63wjPj5egwYNytLDOqyvGezbt0///POP0+XlNra24bPPPqutW7falf+ll17SunXrnKo7J50XelpcXJxefvllnTlzxqn8Cxcu1OnTpy3S6tWrl+76gwYNUqVKlSzSjhw5oq5duyomJsbh+jMah7Ro0cJiefXq1Vq2bJld5S5fvtyufghZ58nrCnfCccRd5/DNmzdX4cKFLdI+++wzU/9gS2pqqp5++mnTA2IcYf1dXr16VRs2bHC6PNj2v//9z5T26KOPav78+Znm/fvvv9WzZ88cfXx15d+L3OHVV181/XZ//PFHvfDCCw5vh5SUlFw/zrXV17399tuma8Tp+eyzzzR79uzsaBoAAAAAAF6HoHAAAAAAAOB2Bw4cUIcOHXT58mWL9IYNG2rlypWmm5fgOX379rVYTkpK0v3335/hLD0xMTF67rnn9Oijj6bNAuVskH/z5s0tlq9evap+/frp4MGDDpdVsWJFm8EO06ZNU7NmzbRkyRK7bsS5du2afvzxR/Xs2VNVqlTRF198ofj4eIfb406zZs1SsWLFLNL27dunxo0b6+uvvzbNfGgtMTFRS5YsUffu3dW2bVun2jBkyJAM94OSJUuqZ8+eTpXtaYmJidq2bZteeukl1alTR3v37jWtM3DgQLVq1cqt7SpUqJB+/vln00zYS5YsUaNGjTR79uxMt7307022Cxcu1KBBg1S+fHm9/fbbGd6ca91vSNJzzz2nr776Kt3fWEpKir788ku1adNGUVFRae13hwceeEBLliwxzWD21Vdf6ZFHHsl0BtrChQvbnGHzySef1H//+990+4fk5GS9++676t+/f9p2KFCggMPtb968uWmGmdTUVA0ePFjjxo1TYmKizXwpKSmaNGmSevXqZVqnV69eppnCMtOuXTtTwOHt7An2vPfee1WwYMF032/VqpXTgcy5Rf78+SX9G9zarl07HTlyJN11//jjD7Vq1coUYFq9evUsBcbm5v7clv79+5tmRz9//rwmT55sc/0BAwbokUcesUhLTk7WyJEj9eCDD2rPnj121Xv27Fl9+umnatasme677z4tWrQo3XXXrFmjjh07qnbt2nrnnXd06NAhu+rYv3+/2rdvbwoS6Nu3b4a/ta+++kqBgYEWaZs3b1bLli21Y8eOdPMdOnRIbdu2NQWw58mTx+6ZykaMGGFKe+WVVzR16tR0jzHx8fF6//331blzZyUkJKT9jjzNneOz++67T2PHjjWlT5gwQW3bttXatWvtanN0dLSmTZumDh06qG7dupo1a5ZDM7XnBP7+/nriiScyXMfVD764tU9+//336tmzZ4Yzxs+ePVvt27dXbGysRXqbNm00ePDgTOvyRB8F93PnPlW2bFl16tTJIu3s2bPq1KlThkErO3bsUFhYWFqAh7N9s/U1g9TUVD300EPatm2bU+XlNq1bt9bQoUMt0q5du6aOHTtmOAt3dHS0Bg0apI8++kiSc+cpOe280JOSk5P14YcfqlKlSurVq5dmz55tV0BsamqqZsyYoUGDBpnes5V2S548efTLL7+YHo62Zs0aNW7cWHPnzs30+tj169f1yy+/qFWrVqbjyu1s7Qf9+vUzzYJ8u5s3b2rChAl64IEH0h7EdCfsB57kyesKuf044s5z+AIFCpge1BMXF6f27dvrwIED6eY7duyYunfvrq+//tqizY6y/i4lafjw4QoPD0/7GwGyrlevXqa+NTExUQ8++KD69euntWvXmr7vrVu36oknnlCbNm3SHup37733uq3NruTKvxe5Q/Xq1TVp0iRT+scff6x27drZ1decP39en376qe6+++4cPcu7PapUqaLXXnvNIi05OVl9+vTRhx9+mO71hxs3bujFF1/Uf/7zH0mSj4+PaZwDAAAAAEBu45/5KgAAAAAA4E6xbds21a9f3yVlTZgwQT169LD53nPPPafIyEhTekxMjMLCwrKt3sx06dJFefPmzVL90r+znU+bNi3L5Thi0aJFLtl2L7/8ssVsJM8//7y++OILi5mCLly4oDZt2qhVq1bq1KmTKlSoIB8fH124cEEbN27U77//bjFTZLt27VSmTBl9//33DrdnyJAheuONNyyCYpYuXaqlS5eqaNGiCg0NNd3cUbp06XRnHRo6dKgOHjxompV3165d6t69u8qVK6c2bdqoXr16Kl68uAICAnT16lXFxMToyJEj2r59u/bu3ZvuzZDeqnz58po9e7Z69OihpKSktPSLFy/qiSee0BtvvKEOHTqoUaNGKlGihPLnz6+YmBj9888/2rFjh9atW5d2Q3J6M4dmJjAwUEOGDNEXX3xh8/0RI0Z4XbDniBEjTEFvt0tOTlZsbKwuXLhg8b1aa9Gihd0zorlau3bt9Nlnn+nJJ5+0SD9+/LgGDRqkF198UWFhYWnbPjAwUNeuXVNMTIxOnDih7du3a9euXTZnxM2ozlatWunvv/9OS0tOTtZTTz2lTz/9VL169VLNmjVVoEABRUZGat++fVq4cKHOnTuXtn5oaKhefPFFt83o2r59e61YsUJdu3a1uPl+5syZun79un788ccM989hw4ZpwYIFFgFRhmHo/fff17fffqvevXurXr16Cg4O1pUrV7R//379+uuvFp+5W7duunbtmtasWeNw+ydNmqS1a9dq3759aWnJyckaP368Jk+erF69eqlu3bpp9R84cEDz58+3ORtt2bJlnTqGFS9eXPXr19fOnTttvm9PUHjevHnVsmVLLV++3OkycruxY8fqjTfeUEpKitavX69atWqpffv2acfaxMREnTp1SosXL9b27dtN+fPly6fp06dnKSg2J/bnWeHr66uxY8eqX79+Funvv/++Ro4caXqghCRNmTJFx44dMwXazp8/X/Pnz1e9evXUunVrVa1aVcWLF5evr69iYmIUHR2tffv2afv27Tp69KjDs0bt379fr7/+ul5//XVVqFBBDRo0UL169RQaGqoiRYrI399fsbGxaW1bv369qY7ixYvbnEn4dpUrV9ZXX32lIUOGWKTv2rVLTZo00X333af7779fZcuWlZ+fnyIiIrRq1Sr99ddfNgOd33nnHTVu3Niuz3jPPffogQce0MKFC9PSUlJSNHLkSH355Zfq1auXqlSporx58yoyMlLbt2/XsmXLdOnSpbT1P/nkE6+Yzd7d47MxY8bo0KFDphkfV69erVatWunuu+9WWFiYatWqpWLFiilfvnyKiYlJO25s375dBw8ezHVB4LY8/vjjeuutt2yO7woWLGja97NqwoQJaWOeRYsWaeXKlerSpYtatGihUqVK6fr16zp27JgWLFhg86EPRYoU0bRp0zJ8OMvtPNVHwX3cvU9NmDBBK1assOgfNm/erGrVqql379667777FBwcrLi4OJ0+fVp//vmnxTGoatWq6t69e1oAsiMeeOABFStWzOKhg5s3b1aTJk0UFBSk0qVL2xz37Nq1y+G6cqqPP/5Y4eHhFrNQx8TEaNiwYXr77bfVu3dvVa1aVYGBgbp48aI2btyoJUuWWFzXefPNN/XSSy85VG9OPC/0tJSUFP3222/67bfflCdPHtWtW1cNGjRQ9erVVbRoURUuXFhJSUm6dOmS9u/fr+XLl9ucXXzgwIGZBvs1btxYX3zxhR5//HGL/vz48ePq27ev7rrrLnXq1El16tRRcHCw/P39FRMTo5MnT2rHjh1av369bty4Ienfhw+kZ8iQIXr33Xd1/PjxtLS4uDg99NBDatiwobp3764qVaooT548unTpkrZv364lS5YoOjo6bf1atWqpW7dupmt5cC1PXlfIzccRd5/D//e//9UPP/yQFvgr/Rv0Xa9ePXXv3l1hYWEqWbKk4uPjFRERofDwcIWHh6edpwUHB+u5556zORt1Zpo2baqaNWtaBKAfOXJEbdu2VYECBXTXXXfZPH9etmyZSpcu7XB9d7LJkyfr4MGDpgeTzpkzR3PmzFFAQIBKliwpPz8/nT9/3uKYLv37cOYxY8aoc+fOFul+fn7Z3vascvXfi9zhmWee0ZYtW/TDDz9YpIeHh6tJkyaqW7euOnTooEqVKik4OFhJSUm6cuWKDh48qG3btmnbtm131IMVXn/9dS1ZssSiT0xISNDLL7+sTz/9VA8++KBq1KihokWLKjIyUjt37tSCBQss+vGnnnpKixcvNj0EEQAAAACAXMUAAAAAAAB3pJMnTxqSsu01ffr0dOtu3bq1R+p1Vxtat27tkm2UnvDw8Gxr+8cff2yqb+nSpYafn59T5dWuXdu4fPmyMXToUIv08uXL2/15x40b51Cd9pT9xRdfGHnz5nXZ97Z169YM68vK57+drW0fHh7uUP5ixYpl6bM623bDMIyDBw8aPj4+pjL9/PyMM2fOOF2uK1hvI1e9Hn74YePatWt2t8O6b3JVfzJv3jwjKCjIZZ9r7ty5GdZ3+vRpIzQ01KmyCxUqZGzbts2YPn266b2TJ09m+lnLly9vkWfo0KF2f0/bt283ihcvbqq3S5cuxs2bNzPMe+PGDaNt27ZOfebq1asbly9fztL2v3TpknHPPfdkabvWqFHDOH36tN11Wnv55Zdtluvj42NcuHDBrjI+/PDDdNu3Z88eh9vkqt+Us/tjVqTX53/xxRdObd+8efMaixcvdknbclp/7six0pbU1FSjdu3apnLff//9dPPcvHnTGD58uMv63YIFC6Zb1wMPPOCSOooUKWKsWbPG7u/l22+/Nfz9/Z2uz8fHJ8PvMD3nz583Spcu7VSdL7/8smEYhil97NixmdY7duxYUz5XcOf4LCUlxXj99ddt/n6dfUVGRrrke3CWrd+8veeEGenfv7/Nz/vYY49lqdz0jifpHUMzexUuXNjYsmWLw+1wZx+Vkzg7bnCmT7HFmfNGb9mnxo8f71R9pUqVMo4dO5alPnbGjBkO1+tJzu4vWdnPjh07Ztx1111ObaP+/fsbqampTtWfU88L3e3KlSsu64/DwsKMq1ev2l33zz//bBQoUCBLdWbWV+7YscMICAhwquwyZcoYJ0+edLqPyMrv5nauuq7n7Tx5XSE3HEe85Rzemc8jyQgMDDQ2bdqUpesff/75p8N/R8juaysZyeq19qyUkdW6IyMjjfr16zu8nWvXrm2cO3fOWLlypem9Xbt2ZVqvN1xny46/F2W3lJQU48UXX3Tqt3n7K7PjmCvGP7b+duzMOXZWtnFkZKRRp04dp76jli1bGvHx8TlqLAgAAAAAgDN8BQAAAAAAAGSgS5cumjt3rgoVKuRQvm7dumnt2rUqWrRolur/3//+p7ffftsls7jf8tRTT2nt2rVq0aJFlsopUKCA+vfvr3LlyrmoZdkrLCxMW7ZsUdeuXZ0uIzQ01Om81atXV7t27UzpXbt2VdmyZZ0u19v4+PioVatW+uOPP/Tjjz9mONu4uzz44IPatm2bunXrlqVy/P391a1bN9WtWzfD9cqVK6e//vpL1apVc6j8atWqacOGDWrUqFFWmum0hg0bas2aNSpVqpRF+rJly9SlSxfTzDq3K1CggBYvXqzhw4c7VGeLFi30999/Z7mvLFGihMLDwzVy5Ej5+/s7lNfHx0cDBgzQ+vXrs9SfpTeTd+3ate3uO9IrIzQ0VHXq1HG6bbnJU089pW+++cah2b7Lli2rpUuXZrkPuOVO6c9v8fHx0bhx40zpEydOTLdfyJ8/v7799lv98MMPqlSpUpbqDwkJ0ZNPPpnu+yVLlsxS+dK/fdH69evVqlUru/MMHz5cv//+u+6++26H6ytbtqzmzZvn1MyfJUuW1Lp161SlShW78+TNm1eTJk3SBx984HB92c2d4zNfX1+99dZbWrZsmerVq+d0fZJUuHBhjRgxwivGOdnh6aeftpk+atSobKnvgw8+0Pjx4x2ana9WrVr666+/1KRJE4frc2cfBc9w9z41ZswYjR8/3u7ZxaV/x94bN25U5cqVHa7vdkOHDtW0adMUFBSUpXJys8qVK2vNmjW67777HMr35JNP6ocffnBou94up54Xupu/v7+KFy+epTLy5MmjF154QcuXL3fo+l2/fv20bt26LF0fy2wc0qBBA/3xxx+m8+zMNGvWTJs2bVKFChWcbhsc48nrCrn5OOLuc/ihQ4fqu+++c2gbVqpUSevWrVPTpk0dru92bdu21YIFC7J0/Rj2CQ4O1qZNmzR27FjTzNi2+Pn56YknntD69etVqlQpXblyxbRO4cKFs6OpLpcdfy/Kbr6+vvrwww/1888/O31c8/HxUYkSJVzbMC8VHBysv/76Sz169HAoX+/evbV8+XK7fhMAAAAAAOR0BIUDAAAAAAAgU7169dKePXv0xBNPqECBAumu5+vrq7CwMC1cuFCLFy9WkSJFsly3r6+vXnvtNUVEROiLL75Qv379VLt2bQUHBzt0M521e+65R2vXrtXatWs1cOBAlS5d2q58pUuX1uDBg/X999/r/Pnz+umnnxQSEuJ0O9ytcuXKWrJkiTZt2qSBAwfadSNRSEiIBg4cqCVLlmjjxo1Zqr9x48amtOwKrsluPj4+CgoKUpkyZdSgQQMNGzZMn3/+uY4fP641a9aoY8eOnm6ihbvvvluLFy/W7t279dhjj6lixYp25StevLj69OmjqVOnKiIiQosXL7YrALBmzZratm2b3n777UwDFmvUqKHPPvtMe/bsUa1atexqV3apVauW1q5da7pBLzw8XB06dLB50+QtAQEB+vbbb7V69Wp16tQpwxtwa9asqWnTpmnNmjUuu6EvICBAkydP1r59+zR8+PBMv/dixYrp4Ycf1vbt2zV79uwsB6a3bNnS5k136QV621K3bl2bfaqtAOQ72YgRI7Rnzx4NHjw4w+Ny2bJl9dprr+nAgQMObQd75Kb+3B69e/dW/fr1LdKioqL02WefZZhv4MCBOnLkiGbPnq3OnTvbHWhQs2ZNPfvss1q2bJkiIiIyDGaeMmWKTp06pS+//FJ9+vRRmTJl7KqjQIEC6tOnjxYvXqy1a9eqZs2aduW7Xfv27bV//35NnTpV9913X4bBhz4+PmrUqJEmTZqkI0eOqHfv3g7Xd0vFihW1Z88evfPOOxkGGOXNm1f9+vXTzp079cILLzhdX3Zz9/js/vvv165du7R48WL17t1bxYoVsytfpUqV9Nhjj2nevHk6f/68w8EtOUm9evWUJ08ei7SmTZuqQYMG2VbnmDFjtHnzZj3wwAOmum9XrVo1ffDBB9q5c6caNmyYpTrd0UfBc9y9T40ZM0ZbtmzJdBxcpUoVff7559q8ebPKly/vdH23e/TRRxUREaHp06dr8ODBatCggUJCQjIcJ91pKlWqpLVr1+qbb77JsC/z9fVVu3bt9Ndff+nLL7906MECtuTU80J3CgwM1MWLF7V27Vq99tpratWqlQICAuzKW758eY0ePVoHDx7UpEmTnAqCatiwodauXavly5erV69edgUFli1bVo899pjWrFmjX375JdP1W7Rood27d2v06NGZXits3LixZs6cqfXr1+uuu+6y92PARTx5XSE3H0fcfQ7/yCOPaP/+/XrooYcy7BdKly6tt956S3v37s3yQ6Nu6d69u06dOqU5c+bo0Ucf1T333KOSJUuqYMGCTj9kBLbly5dP48aN06lTp/TFF1+oY8eOqlKligoWLKi8efOqZMmSCgsL0/jx43X06FFNmTIl7cEhFy5cMJVn73mhp2XX34vcoV+/fjpy5IimTp2q1q1b2xXYXrduXb366qs6fPiwnnrqKTe00jsEBwdr4cKF+vXXX9WiRYsM+4+mTZvq119/1a+//mr3GAoAAAAAgJzOxzAMw9ONAAAAAAAAQM6RkJCgzZs36/Dhw4qOjlZqaqqKFCmiypUrq0mTJjnm5iFbjhw5ooMHDyo6OlrR0dFKSkpSUFCQChUqpIoVK6p69eo5KgDcHoZhaPfu3Tp+/LgiIyN1+fJl+fv7KygoSGXLllWNGjVUqVIll9y0l5KSoooVK+qff/5JS6tUqZKOHTvGTYEecubMGe3Zs0dRUVGKjo5WfHy8AgMDVahQIZUrV07Vq1e3O7gwI4ZhaM+ePdq1a5eioqJ08+ZNBQUFqXz58qpfv36unfkrOjpaGzZs0Llz5xQVFaX8+fOrbNmyatSoUZZnsrLHrd/3sWPHdOnSJcXExKhQoUIqUaKEKlasqMaNG8vXl2fH5nQ3b97U5s2bdejQIV2+fFn58uVTqVKlVLVqVTVu3Dhb+lf6c+clJydr586dOn36tKKjo3X58mX5+voqKChIRYsWVdWqVVW9evUsz758/vx5HTt2TKdOndLly5d1/fr1tHqCg4NVq1YtVa9e3eEZADMTExOjTZs26eLFi4qMjFRKSopKlCih0NBQNWnSJNvGUXv27NHu3bsVFRWlGzduqHDhwqpWrZruvffeHDmTtTvHZ7fq27t3r44fP542Dk5NTVVQUFDaOL9GjRoueeBTTvH111/riSeesEibMWOGhg4dmqVyZ8yYoUceecQi7eTJk6axUGxsrDZt2qQjR44oNjZWBQoUUOnSpVWrVi3Vrl07S23IiLv6KLiOt+5TV69e1dq1axUREaHo6Gj5+/urTJkyatiwoWrUqOHy+uC4Y8eOadeuXTp37pyuXbumoKAgVapUSc2aNVNwcHC21Hmnnhc6Izk5WcePH9fx48d19uxZxcbG6ubNmwoICFBQUJDKlSunOnXquOR83VpKSoq2b9+uU6dOKSoqSleuXFG+fPkUFBSkChUqqEaNGk7NBH17+du2bdP+/fsVFRWl5ORkBQUFpZ2jZhaEDPfy1HWFnHgcWb16tdq0aWORFh4errCwMIs0d5/D37hxQ+vXr9fp06cVFRUlHx8fhYaGql69eqpfvz7n8HeogQMH6scff0xbLlu2rM6cOePBFt2Zrl+/rs2bN+v8+fOKiorStWvXVLBgQRUpUkRVqlRRzZo1Vbx4cU830ytERERoy5YtOnfunK5cuaKCBQuqQoUKuueee7JlPAQAAAAAgLcjKBwAAAAAAACAWyxevFg9evSwSHvvvff0yiuveKhFAABn0J8DyO0aNWqkHTt2pC0XLVpU586dy/LMc/YG8AL2Yp8CAMA72BsUDnhaQkKCypUrp0uXLqWlPfjgg5o3b54HWwUAAAAAAABHMAUIAAAAAAAAALf4/PPPLZbz58+v4cOHe6g1AABn0Z8DyM02bNhgERAuScOHD89yQDgAAAAAeNrMmTMtAsIlqVWrVh5qDQAAAAAAAJxBUDgAAAAAAACAbLd161atXLnSIm3AgAEqUaKEh1oEAHAG/TmA3O7tt9+2WPb19dXTTz/todYAAAAAgGscO3ZMo0ePtkgrUKCABg0a5KEWAQAAAAAAwBkEhQMAAAAAAADIVsnJyaZAGh8fH/3nP//xTIMAAE6hPweQ2y1evFjLli2zSOvdu7cqVKjgmQYBAAAAgJU33nhDZ86ccSjPxo0bFRYWpqtXr1qkDxw4UMWKFXNl8wAAAAAAAJDNCAoHAAAAAAAAkG0OHz6sHj16aMuWLRbp/fv3V506dTzUKgCAo+jPAeRmSUlJ+vrrrzVw4ECLdD8/P02YMMFDrQIAAAAAsw8//FCVKlVSx44d9eWXX2rPnj1KSkoyrXf58mUtXrxYvXr1UosWLRQREWHxfqlSpfTuu++6q9kAAAAAAABwEX9PNwAAAAAAAABA7lG/fn1JUmpqqs6dO6fo6GjTOoGBgXr77bfd3DIAgCPozwHkZlOmTNGUKVMkSXFxcTpz5ozNIIqRI0eqRo0a7m4eAAAAAGQoJSVFK1eu1MqVKyVJefLkUUhIiAoXLqzk5GRduXJFUVFRMgzDZv68efNq1qxZCg4OdmezAQAAAAAA4AIEhQMAAAAAAABwmd27d2e6zmeffaaKFSu6oTUAAGfRnwPIzS5cuJBpP1ejRg29//77bmoRAAAAADgvKSlJERERptnAbQkNDdX8+fPVvHlzN7QMAAAAAAAArkZQOAAAAAAAAAC3yJs3ryZOnKhHHnnE000BAGQB/TmA3K5hw4ZavHixChYs6Omm3JHq16/vlnp27drllnrgfbZt26YRI0Zkez2NGzfWtGnTsr0euBb7BzyFfQ93onPnzqlLly7ZXk/p0qW1bNmybK/HXXr16qXFixfr+vXrDuULDAzU448/rtGjRys0NDSbWud9Fi1apDFjxmR7PT169NCECROyvR4AAAAAAACCwgEAAAAAAABkCx8fHwUGBqpy5cpq27atRo4cqapVq3q6WQAAB9GfA8jt8ubNq+DgYDVs2FB9+/bVww8/LH9//pTuKZnN4g5kVVxcnFv2syJFimR7HXA99g94Cvse7kSJiYlu2e9jYmKyvQ53+umnn3Tz5k2tXbtWGzZs0O7du3Xy5EmdO3dO169fV3x8vAIDA1WsWDGFhISocePGatWqlTp27KiiRYt6uvlud/nyZbfsZ+56uBUAAAAAAAB/yQYAAAAAAADgMoZheLoJAAAXoD8HkJuNGzdO48aNc3u9w4YN07Bhw9xeL3Iv9ikAALxDWFgY59FwqwIFCqhjx47q2LGjp5sCAAAAAAAAN/P1dAMAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAOnzMXhEJQAAAAAAAAAAAAAAAAAAAAAAAAAAAAB4LWYKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvRlA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAHgxgsIBAAAAAAAAAAAAAAAAAAAAAAAAAAAAwIsRFA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAXoygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAADwYgSFAwAAAAAAAAAAAAAAAAAAAAAAAAAAAIAXIygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAALwYQeEAAAAAAAAAAAAAAAAAAAAAAAAAAAAA4MUICgcAAAAAAAAAAAAAAAAAAAAAAAAAAAAAL0ZQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAB4MYLCAQAAAAAAAAAAAAAAAAAAAAAAAAAAAMCLERQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAF6MoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA8GIEhQMAAAAAAAAAAAAAAAAAAAAAAAAAAACAFyMoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC8GEHhAAAAAAAAAAAAAAAAAAAAAAAAAAAAAODFCAoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC9GUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAeDGCwgEAAAAAAAAAAAAAAAAAAAAAAAAAAADAixEUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAABejKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPBiBIUDAAAAAAAAAAAAAAAAAAAAAAAAAAAAgBcjKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvBhB4QAAAAAAAAAAAAAAAAAAAAAAAAAAAADgxQgKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvRlA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAHgxgsIBAAAAAAAAAAAAAAAAAAAAAAAAAAAAwIsRFA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAXoygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAADwYgSFAwAAAAAAAAAAAAAAAAAAAAAAAAAAAIAXIygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAALwYQeEAAAAAAAAAAAAAAAAAAAAAAAAAAAAA4MUICgcAAAAAAAAAAAAAAAAAAAAAAAAAAAAAL0ZQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAB4MYLCAQAAAAAAAAAAAAAAAAAAAAAAAAAAAMCLERQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAF6MoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA8GIEhQMAAAAAAAAAAAAAAAAAAAAAAAAAAACAFyMoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC8GEHhAAAAAAAAAAAAAAAAAAAAAAAAAAAAAODFCAoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC9GUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAeDGCwgEAAAAAAAAAAAAAAAAAAAAAAAAAAADAixEUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAABejKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPBiBIUDAAAAAAAAAAAAAAAAAAAAAAAAAAAAgBcjKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvBhB4QAAAAAAAAAAAAAAAAAAAAAAAAAAAADgxQgKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvRlA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAHgxgsIBAAAAAAAAAAAAAAAAAAAAAAAAAAAAwIsRFA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAXoygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAADwYgSFAwAAAAAAAAAAAAAAAAAAAAAAAAAAAIAXIygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAALwYQeEAAAAAAAAAAAAAAAAAAAAAAAAAAAAA4MUICgcAAAAAAAAAAAAAAAAAAAAAAAAAAAAAL0ZQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAB4MYLCAQAAAAAAAAAAAAAAAAAAAAAAAAAAAMCLERQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAF6MoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA8GIEhQMAAAAAAAAAAAAAAAAAAAAAAAAAAACAFyMoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC8GEHhAAAAAAAAAAAAAAAAAAAAAAAAAAAAAODFCAoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC9GUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAeDGCwgEAAAAAAAAAAAAAAAAAAAAAAAAAAADAixEUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAABejKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPBiBIUDAAAAAAAAAAAAAAAAAAAAAAAAAAAAgBcjKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvBhB4QAAAAAAAAAAAAAAAAAAAAAAAAAAAADgxQgKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvRlA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAHgxgsIBAAAAAAAAAAAAAAAAAAAAAAAAAAAAwIsRFA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAXoygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAADwYgSFAwAAAAAAAAAAAAAAAAAAAAAAAAAAAIAXIygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAALwYQeEAAAAAAAAAAAAAAAAAAAAAAAAAAAAA4MUICgcAAAAAAAAAAAAAAAAAAAAAAAAAAAAAL0ZQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAB4MYLCAQAAAAAAAAAAAAAAAAAAAAAAAAAAAMCLERQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAF6MoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA8GIEhQMAAAAAAAAAAAAAAAAAAAAAAAAAAACAFyMoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC8GEHhAAAAAAAAAAAAAAAAAAAAAAAAAAAAAODFCAoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC9GUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAeDGCwgEAAAAAAAAAAAAAAAAAAAAAAAAAAADAixEUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAABejKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPBiBIUDAAAAAAAAAAAAAAAAAAAAAAAAAAAAgBcjKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvBhB4QAAAAAAAAAAAAAAAAAAAAAAAAAAAADgxQgKBwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAvRlA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAHgxgsIBAAAAAAAAAAAAAAAAAAAAAAAAAAAAwIsRFA4AAAAAAAAAAAAAAAAAAAAAAAAAAAAAXoygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAADwYgSFAwAAAAAAAAAAAAAAAAAAAAAAAAAAAIAXIygcAAAAAAAAAAAAAAAAAAAAAAAAAAAAALwYQeEAAAAAAAAAAAAAAAAAAAAAAAAAAAAA4MUICgcAAAAAAAAAAAAAAAAAAAAAAAAAAAAAL0ZQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAB4MYLCAQAAAAAAAAAAAAAAAAAAAAAAAAAAAMCLERQOAAAAAAAAAAAAAAAAAAAAAAAAAAAAAF6MoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA8GIEhQMAAAAAAAAAAAAAAAAAAAAAAAAAAACAFyMoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC8GEHhAAAAAAAAAAAAAAAAAAAAAAAAAAAAAODFCAoHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAC9GUDgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAeDGCwgEAAAAAAAAAAAAAAAAAAAAAAAAAAADAixEUDgAAAAAAAAAAAAAAgP/H3p1HV12dewN/EsJslRlnFBGQSSoqiIpQbVUqimMVtYBDr1r7VnF4HV411Nmq6K3VqxURpzpLqdyrdcIBERAnQAExIIIiQUEgTIGc9w+XuT1JCOeEQH7A57OWf+zn7L2ffVz+417nmw0AAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAACTc2LFjIycnJ+2fsWPHbpbe+fn55XoDAAAAADWvJu8Nq9rbfSMAAAAAAABA1QmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkWF5NHwAAAAAAAAAAyE7v3r0jlUrV9DEAAAAAAAAA2Ey8FA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYHk1fQAAANjWpFKpmDx5cnz++efx9ddfR3FxcTRp0iTat28fBx54YNSrV2+T9V69enWMGzcu5s6dGwsWLIhatWpFy5Yto3PnztG1a9fIycnZJH2Li4vjs88+i6lTp8b3338fS5cujZycnKhfv340atQodt9992jdunXssccem6Q/AAAAALB+NXlnWR3mzp0bn3zySRQWFkZhYWHUqlUrmjVrFjvvvHMcdNBBsd1229X0EQEAAABgq7NixYqYNGlSfPPNN7Fo0aL44YcfSn8TuPfee0eHDh2iadOm1dYvlUrFRx99FJ988kksXLgw1q1bFzvttFPsvvvu0bNnz6hbt2619QIASCqhcAAA2EyKiori5ptvjkcffTTmzp1b4ZyGDRvGqaeeGldffXXsueee1dZ7zpw5kZ+fHy+88EIsXbq0wjk77rhjnHfeeXHJJZdU248k33jjjbj//vtj9OjRsXLlyg3Ob9asWfTo0SOOPfbYOP7446NZs2bVcg4AAAAA2NqMHTs2+vTpk1Z74403onfv3hnvUZN3lhtr/vz5MWzYsBgzZkxMnz59vfNq164dPXr0iN///vdxyimnbLI/jAkAAAAA24JVq1bFgw8+GM8880y89957sWbNmvXOzcnJiS5dukTfvn1j8ODBsffee1c6999dd911kZ+fHxERy5YtizvuuCPuv//+WLBgQYXrd9hhh+jfv3/k5+dn/ThNfn5+DB06NK2WSqWy2iPix99plr1DHTFiRAwaNCjrvQAA1ie3pg8AAADbgtdeey06dOgQN95443p/XBnx448whw8fHp06dYqRI0dWS++77747OnbsGCNHjlxvIDwiYsGCBZGfnx8dO3aMyZMnb1TPxYsXxwknnBC/+MUv4qmnnsooEB4RsWjRonjxxRfjd7/7XVx44YUbdQYAAAAAYP1q8s5yY6xcuTIuu+yyaNOmTdxxxx2VBsIjIoqLi+Ptt9+OU089Nbp27RpTp07dTCcFAAAAgK3Lf/3Xf0Xr1q3jD3/4Q7z11luVBsIjfgxWf/zxx3HzzTdHu3bt4rnnnsu656RJk6Jjx44xdOjQ9QbCIyJ++OGHGDlyZHTs2DHuvvvurPsAAGwpvBQOAACb2IsvvhgnnnjiBi9A/92KFSti0KBBsXLlymjfvn2Ve1999dVx0003ZbVm7ty5cdhhh8Wbb75ZpZ6LFy+O3r17xyeffFKl9QAAAADAplWTd5YbY8GCBXHcccfFxIkTq7T+k08+iZ49e8aTTz4Zffv2rebTAQAAAMDWadWqVXHOOefE448/XuU9UqlULFu2LKs177//fvTp0yeKiooyXrNixYq46KKLorCwMG644YZsjwkAkHhC4QAAsAmNHz++wh9X5uTkRI8ePaJv376x2267RV5eXsybNy9efvnleOutt2LdunUREXHhhRdmHer+yZ133lnh2rp168ZRRx0VvXr1ip133jmKiopi9uzZ8Y9//KP0lZyioqLo379/nHTSSVn3HTJkSIWB8LZt28YRRxwR7du3j6ZNm0bdunVj+fLlsWTJkpg5c2ZMnTo1JkyYEKtXr87+ywIAAAAAGanJO8uN8e2330aPHj3iyy+/LPdZp06d4rDDDouOHTtGo0aNIiJi4cKFMX78+Pjv//7vtB+bLlu2LE488cR499134+c///nmOj4AAAAAbJGKi4vjyCOPjLfeeqvcZ7m5udGtW7c4/PDDY/fdd4+mTZvGqlWr4rvvvospU6bEhAkT4tNPP61S3yVLlkT//v3TAuE///nP49hjj41WrVpF3bp1Y/78+fHaa6/Fa6+9FmvXrk1bf+ONN0bTpk3j4osvrlJ/AICkEgoHAIBNZNWqVXHWWWeV+3Fl27ZtY8SIEdGzZ89ya/7v//2/8cknn8RZZ50VkydPjnXr1kV+fn7WvWfMmBFXX311ufrRRx8dDzzwQOy6667lPrvhhhvihRdeiPPPPz++/fbbmDdvXtx///1Z9f3qq69i5MiRabXmzZvH8OHDo1+/fhtcX1RUFK+88ko8+OCDUatWrax6AwAAAACVq8k7y41RUlISAwYMKBcI79mzZ9x5553RvXv3Ctf98Y9/jCVLlsT1118fw4YNi1QqFRE//ns48cQT4+OPP46f/exnm/z8AAAAALCluvjiiysMhJ9wwglx0003Rbt27SpdP2vWrPj73/8ef/3rX7Pqe//998eqVasiImKXXXaJBx54IPr27Vtu3mWXXRYzZsyIwYMHx/jx49M+u+qqq6Jv374bPCMAwJYkt6YPAAAAW6vbbrstpk+fnlbbZ599Yty4cRX+uPInXbp0iTfffDMOOuigiIhYuXJl1r3PP//80gvRn5xyyinx4osvVhgI/8nxxx8fb775ZrRo0aJKvUePHl36w8qfPPPMMxkFwiMiGjZsGP37948XX3wx/va3v2XVGwAAAACoXE3eWW6M22+/PV5//fW02u9///t455131hsI/0mjRo3ijjvuiOHDh6fVZ8+eHffdd1+1nxUAAAAAthYvvfRSuTB3Tk5O3H777fHcc89lFLZu06ZNXHPNNTFnzpw46qijMu790+8fd95553jrrbcqDIT/pF27dvH6669H7969y+1xwQUXZNwTAGBLIBQOAACbQHFxcbkfFNauXTuee+65aNas2QbXN2zYMF544YVo1KhR1r2nTJkSb7zxRlqtTZs28cgjj0Ru7ob/F6Bdu3bxyCOPZN03IqKgoCBtvPfee8dhhx1Wpb0aNGhQpXUAAAAAQHk1eWe5MVasWBF//vOf02q//vWv45577omcnJyM9xk8eHCcc845abVhw4aVezUdAAAAAPjRn/70p3K1K6+8Mi655JKs96pXr17suOOOWa97/PHHo3Xr1hnt/+yzz0bTpk3T6q+//npMnTo1674AAEklFA4AAJvAqFGjYsGCBWm1Cy+8MPbZZ5+M92jZsmVcc801Wff+r//6r3K1O+64I+rWrZvxHkceeWTGr3v/u2XLlqWNy16wAgAAAAA1oybvLDfGQw89FIsWLSod5+bmxl/+8pcq7XXttdemBckXLFgQ48eP3+gzAgAAAMDW5u233y53d9axY8cYOnToZjvDiSeeWO7178o0bdo08vPzy9Ur+k0lAMCWSigcAAA2gf/5n/8pVzv33HOz3mfQoEFRp06djeq90047xa9//euse//Hf/xH1mvKhsCnTJkSP/zwQ9b7AAAAAADVqybvLDfGs88+mzb+xS9+EXvuuWeV9tptt92ic+fOabWxY8dW9WgAAAAAsNUaPXp0udqQIUMiLy9vs52hKveXZ555ZtSrVy+tVtHdKADAlkooHAAANoH33nsvbdy+ffusXtz5SZMmTbL6S5cLFy6M2bNnp9WOO+64qFWrVta9jzzyyGjYsGFWa7p37542LioqilNPPTW+//77rPsDAAAAANWnpu4sN8bq1atjwoQJabWDDz54o/YsGyj/8MMPN2o/AAAAANgalf1jirVr145TTz11s/Xfbrvt4ogjjsh63Q477BCHH354Wq2goCAKCwur62gAADVq8/2JHgAA2EasWLEipk+fnlbr1q1blffr1q1b/Otf/8po7uTJkytcXxV5eXnRpUuXGD9+fMZrjjzyyNhpp53im2++Ka299NJL0bp16zj99NPjpJNOikMOOSRq165dpTMBAAAAANmryTvLjTF58uRYtWpVWu2hhx6KUaNGVXnPuXPnpo0XLVpU5b0AAAAAYGu0evXqcn9MsWvXrtGgQYPNdoZ99923So/hRETst99+MWbMmLTa5MmT46ijjqqOowEA1CihcAAAqGaFhYWRSqXSau3atavyfu3bt8947sKFC8vVNrZ3NqHw+vXrxz333BMnnXRS2r+DH374Ie6999649957o0GDBnHQQQdF9+7do3v37nHooYdG48aNq3xGAAAAAKByNXlnuTHmzZtXrvbVV1/FV199VW09vvvuu2rbCwAAAAC2BosWLYp169al1Tp37rxZz1Dd95cV/bYSAGBLlFvTBwAAgK3NkiVLytV22GGHKu+Xzdqa7P2TE044IR577LFo2LBhhZ+vWLEiXnvttbjpppviuOOOi2bNmsX+++8ft956a7X+mBMAAAAA+FES7g2rYnMEtleuXLnJewAAAADAluT7778vV9vcD79U9/1lRXekAABbIqFwAACoZsuWLStXW19AOhPZrK3J3v9uwIABMWPGjLjgggviZz/7WaVzS0pKYvLkyXHFFVfEXnvtFeecc04UFhZWqS8AAAAAUF5S7g2ztXjx4s3SBwAAAAD4X0uXLi1X22677TbrGar7/rKiO1IAgC2RUDgAAFSzikLQRUVFVd4vm7U12busXXbZJf7617/Gt99+G88//3xceOGFse+++0atWrXWu6a4uDiGDx8eXbp0iQ8++KDKvQEAAACA/5Wke8Ns1K9fv1ztvvvui1QqVW3/zJkzZ7N8FwAAAADYUmy//fblasuXL9+sZ6ju+8sNPW4DALClyKvpAwAAwNamUaNG5Wo//PBDlffLZm1N9l6f+vXrx/HHHx/HH398RPx4Ofzee+/FO++8Ey+99FJMmjQpSkpK0tYsWLAgfv3rX8fUqVOjadOmG30GAAAAANiWJfHeMBPNmjUrV/v+++83S28AAAAA2FZV9Ju9xYsXb9YzVPf9ZUV3pNWtuLh4k/cAAPBSOAAAVLPmzZtHTk5OWm3GjBlV3m/69OkZz23RokW52ubqnantttsujjjiiMjPz4/33nsvvvzyy7jyyiujXr16afMWLFgQt912W7X3BwAAAIBtTU3eWW6Mli1blqt9+eWXm6U3AAAAAGyrmjVrFnl56W9QfvLJJ5v1DDNnzqzy2oruPiv6beVPateuXa5WlYD3d999l/UaAIBsCYUDAEA1a9CgQbRv3z6tNnny5Crvl83abt26bdT6f7d27drNcpG76667xk033RT/+te/olatWmmfPffcc5u8PwAAAABs7WryznJj7L///pGbm/6zhrfeemuz9AYAAACAbVWdOnViv/32S6t99NFHUVRUtNnO8NFHH8W6deuqtLai+8uKflv5k+23375cbenSpVn3nTVrVtZrAACyJRQOAACbQI8ePdLG06dPr9LrOYsXL46xY8dmPL9Fixax5557ptVGjx4dJSUlWfd++eWXN+sl7qGHHhr9+vVLq33xxRexYsWKzXYGAAAAANha1dSd5cZo0qRJuR9rTp8+PT799NPN0h8AAAAAtlW9e/dOG69duzaefPLJzdZ/+fLl8dprr2W9bunSpeXWtW7dOpo3b77eNY0aNSpXKygoyLr3m2++mfUaAIBsCYUDAMAmcPTRR5er/e1vf8t6n5EjR8aaNWs2qvfXX38dY8aMybp3Vc67scq+VhQR8cMPP2z2cwAAAADA1qYm7yw3xnHHHVeudsstt2y2/gAAAACwLTr++OPL1YYNGxZr167dbGeoyv3lo48+GqtWrUqrVXQ3+u/atWtXrjZx4sSs+v7www/x1FNPZbUGAKAqhMIBAGAT6N+/f7Rs2TKtds8998SMGTMy3qOwsDD+9Kc/Zd37vPPOK1e79NJLs/qh5quvvhr/+Mc/su69sb755pu0cU5OTjRr1myznwMAAAAAtjY1eWe5MS688MJyL/U89thj8cILL2zWcwAAAADAtqRHjx7Rq1evtNq0adPiuuuu22xnePbZZ+Ptt9/OeP73338f+fn55eoV/aby33Xp0iVq166dVnviiScy7hsRMXTo0Fi2bFlWawAAqkIoHAAANoHatWvHBRdckFZbs2ZNnHjiifHdd99tcP2KFSvihBNOiMWLF2fdu3PnztGnT5+02syZM2Pw4MFRUlKywfWff/55nHnmmVn3jYjIz8+PCRMmVGntV199Ve6HnPvss0+5y1YAAAAAIHs1eWe5MXbYYYe47LLL0mqpVCp++9vfbtQftvyf//mfOP/88zf2eAAAAACw1br22mvL1W6++ea48847s95r9erVsWDBgqzXDRgwIObMmZPR/qecckosWrQord6nT5/o1KlTpWvr1asXvXv3Tqu9++678dxzz2V0xkcffTTuuuuujOYCAGwsoXAAANhELr/88mjXrl1abdq0aXHIIYfEe++9t951U6dOjd69e8c777wTERH169fPuve9994bdevWTas98cQTceyxx8b8+fPXu27UqFHRq1ev0svXbHuPGjUqevToET169Ii777475s6dm9G6d999N37xi1/E0qVL0+pnnHFGVv0BAAAAgPWryTvLjXH55ZfHEUcckVZbvnx5HH/88fG73/0uCgoKMtrn888/j5tuuik6deoUffv2zeqVIQAAAADY1hx++OExZMiQtFoqlYpLLrkkTjrppJg5c+YG95g9e3bceOONsccee8RLL72Uce969epFRMS8efPi0EMPjZdffnm9c2fOnBmHH354vPbaa+X2uO+++zLqd84555Sr/fa3v41Ro0atd82SJUvisssui4EDB0YqlSo9MwDAppSTSqVSNX0IAADYWo0fPz569+4da9asSavn5OREz549o2/fvrHbbrtFbm5uzJ8/P/71r3/F2LFjY926dRERUatWrbjxxhvjiiuuSFv/xhtvlPvLlGXdeeedcckll5Sr16tXL44++ug49NBDY6eddoqVK1dGQUFB/OMf/4gpU6aUzttll13i5JNPLvcXLCv7X4iuXbvGxx9/nFZr165ddO3aNTp37hzNmzePRo0aRcSPF6IzZ86MN954Iz744INye+29997x0UcfRYMGDSr9ngAAAACwLRo7dmz06dMnrZbJvWFN3lnm5+fH0KFD02qZ/mRh8eLF0bNnz5g+fXq5z2rVqhX7779/9OrVK/bcc89o0qRJlJSUxJIlS6KwsDA++eSTmDx5crkXhTp27BhTp07NqD8AAAAAbIvWrl0bv/rVr+KNN94o91lubm7sv//+cfjhh0erVq2iSZMmsWrVqvj+++9j6tSpMWnSpLTfE44YMSIGDRpUYZ+cnJy08R//+Md45pln4uuvvy6tdevWLfr16xd77LFH1KlTJ+bPnx+vv/56vPrqq1FcXFxuzzvvvDMuvvjijL9njx49YvLkyeU+O+igg+KYY46JPfbYI3JycuLbb7+N9957L1566aX44YcfSs//17/+NS644IK0tZV9ZwCAqsir6QMAAMDW7KCDDornnnsuTjzxxLQfWaZSqRg3blyMGzeu0vV/+ctfYp999qlS7yFDhsSiRYvi5ptvTquvWrUqXnjhhXjhhRfWu7Zhw4YxatSoePHFF6vU+9/NmDEjZsyYEU899VTGa3bdddd44YUXBMIBAAAAoJrV5J3lxmjcuHG8++67ceaZZ8aYMWPSPlu3bl1MmDAhJkyYsNnPBQAAAABbs7y8vPjv//7vOOuss+Lvf/972mclJSUxceLEmDhxYrX3bdSoUYwaNSr69OkTRUVFERExefLkCkPbFbnqqqsyDoRH/Pg9R44cGQcddFAsW7Ys7bPx48fH+PHjK13/l7/8JY4++uiM+wEAVFVuTR8AAAC2dsccc0yMGTMmdtttt4zX1K9fP4YPHx7nn3/+RvW+6aabYtiwYVmFq3fdddd44403Yv/998+634477pj1mrL69esX7733XnTs2HGj9wIAAAAAyqvJO8uN0bhx4/jnP/8Zd911V7Rs2XKj9mrVqlUMHjy4mk4GAAAAAFuvevXqxRNPPBF/+ctfokWLFlXaIy8vL5o2bZrVmgMOOCBee+212GWXXTJe06BBgxg2bFjceOON2R4xOnbsGG+88UZW33G77baLJ554In7/+99n3Q8AoCqEwgEAYDM44ogj4tNPP42rr7660h9a1q9fPwYOHBhTpkyJs846q1p6X3TRRTF16tQYOHBgbL/99uud16JFi/h//+//xbRp0+KAAw6oUq+XXnopPv3007j99tvjmGOOiWbNmmW0bocddoiBAwfGm2++GaNHj87qEhcAAAAAyF5N3llujJycnPjjH/8Yc+bMiXvvvTf69OkT9erV2+C63Nzc2G+//eLyyy+PsWPHxuzZs+OSSy7ZDCcGAAAAgK3DhRdeGAUFBXHbbbfFgQceGLm5lUeScnNzo3v37nH99dfHnDlzol+/fln37N69e0ybNi2uuuqqaN68+Xrnbb/99jFw4MCYOnVqXHTRRVn3+Um3bt1ixowZcdlll0WTJk3WO69hw4Zx7rnnxqeffhqnnXZalfsBAGQrJ5VKpWr6EAAAsC1JpVLx/vvvx8yZM+Obb76JNWvWRJMmTaJ9+/bRvXv3qF+//ibrvXr16njnnXdi7ty5sWDBgsjNzY2WLVtGly5domvXrhu8pK2KuXPnxhdffBFz5syJJUuWRFFRUdSuXTu23377aNGiRXTu3DnatGmzSXoDAAAAABtWk3eW1WH16tXx/vvvx/z58+O7776LxYsXR15eXvzsZz+LZs2aRdu2baNdu3YZhccBAAAAgMwsXrw4Jk2aFN9++20UFhbGypUro2HDhtGkSZNo27ZtdOjQodKHbP5dTk5O2vi6666L/Pz8tFpJSUl8+OGHMWXKlPj2228jlUpFy5YtY/fdd49DDjkk6tatW11frbTfpEmTYvr06VFYWBhr1qyJxo0bR4cOHaJHjx7V3g8AIBNC4QAAAAAAAAAAAAAAAECNyCQUDgBAhKf4AAAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMGEwgEAAAAAAAAAAAAAAAAAABJMKBwAAAAAAAAAAAAAAAAAACDBhMIBAAAAAAAAAAAAAAAAAAASTCgcAAAAAAAAAAAAAAAAAAAgwYTCAQAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMHyavoAAAAAAAAAAAAAAAAAwLYplUrV9BEAALYIXgoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEiwvJo+AGyLlixZEm+++WbpeLfddou6devW4IkAAAAANo/Vq1fHV199VTo+7LDDolGjRjV3INhKuYMEAAAAtlXuIGHzcAcJAAAAbKtq8g5SKBxqwJtvvhn9+/ev6WMAAAAA1LhRo0bFcccdV9PHgK2OO0gAAACAH7mDhE3DHSQAAADAjzbnHWTuZukCAAAAAAAAAAAAAAAAAABAlQiFAwAAAAAAAAAAAAAAAAAAJFheTR8AtkW77bZb2njUqFHRpk2bGjoNAAAAwOYza9as6N+/f+m47D0JUD3cQQIAAADbKneQsHm4gwQAAAC2VTV5BykUDjWgbt26aeM2bdpEx44da+g0AAAAADWn7D0JUD3cQQIAAAD8yB0kbBruIAEAAAB+tDnvIHM3WycAAAAAAAAAAAAAAAAAAACyJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJllfTBwAAAAAAAAAAAACApFm2bFmMGzcuZs6cGUuXLo369etHq1atomfPnrHzzjtXa69p06bF5MmT45tvvol169ZF06ZNo1OnTtG9e/fIy/NzXwAAAACEwgEAAAAAAAAAAABIoEGDBsXIkSOrZa9WrVrFnDlzMpo7e/bsuPbaa+Ppp5+ONWvWlPs8JycnDjvssBg6dGj06tWrymdKpVIxYsSIuPXWW2PmzJkVzmnatGmcf/75ccUVV0TDhg2r3AsAAACALV9uTR8AAAAAAAAAAAAAADalOnXqZDTv6aefjk6dOsVjjz1WYSA84scw99ixY6N3795xxRVXRCqVyvo8S5YsiSOPPDLOPvvs9QbCIyK+++67uOGGG6JLly4xbdq0rPsAAAAAsPUQCgcAAAAAAAAAAABgq3bMMcdscM4zzzwTp512WqxYsSKt3rx589hvv/1i1113jZycnNJ6KpWKW2+9NYYMGZLVWVauXBlHHnlkvPLKK2n1OnXqRNu2baNz587lXgUvKCiIPn36xKxZs7LqBQAAAMDWI6+mDwAAAAAAAAAAAAAAZV1++eVxxhlnZL3u888/jwsuuCCtNmjQoErXfPHFFzF48OAoKSkpre27774xbNiw6NOnT2ltxowZcdVVV8Xzzz9fWrvrrrvi0EMPjRNOOCGj8w0ZMiQmTpxYOs7NzY2rr746Lr744mjcuHFERKxZsyaeeOKJGDJkSCxevDgiIgoLC+OUU06JSZMmRa1atTLqBQAAAMDWQygcAAAAAAAAAAAAgMTp0KFDdOjQIet1r7/+etr45z//eXTp0qXSNddcc00UFRWVjg844IB49dVXY/vtt0+b165du3j22WfjvPPOiwceeKC0fvnll8exxx4beXmV/zR3+vTp8be//S2t9thjj8Vpp52WVqtTp04MGjQoDjjggDjkkENiyZIlERHx4YcfxiOPPBKDBw+utA8AAAAAW5/cmj4AAAAAAAAAAAAAAFSHkpKSePTRR9NqG3olfNq0afHUU0+VjuvUqRMjR44sFwj/SU5OTtx9992x9957l9a++OKLGDFixAbPd91118W6detKx2eeeWa5QPi/69ixY9x+++1ptaFDh0ZxcfEGewEAAACwdREKBwAAAAAAAAAAAGCr8Oqrr8a8efNKx7Vr144BAwZUuuahhx6KkpKS0vGpp54a++yzT6Vr6tWrF1dccUVa7cEHH6x0zeLFi+P5558vHefk5ER+fn6layIiBg8eHK1atSodf/nll/Hqq69ucB0AAAAAWxehcAAAAAAAAAAAAAC2CiNHjkwbH3PMMdGsWbNK14wePTptfPbZZ2fU6ze/+U00bNiwdDxp0qT4+uuv1zt/zJgxsXbt2tJx7969o3Xr1hvsk5ubG4MHD06rjRo1KqMzAgAAALD1EAoHAAAAAAAAAAAAYIu3dOnSeOGFF9JqgwYNqnTNjBkzYtasWaXjhg0bRs+ePTPqV3ZuKpWKMWPGrHd+2c9+9atfZdQnIuKXv/xl2vjFF1/MeC0AAAAAWwehcAAAAAAAAAAAAAC2eE8//XSsXLmydNyiRYvo27dvpWs++uijtPGBBx4YeXl5Gfc8+OCDK92vss8yDZ9HRHTr1i3q1q1bOv7666+jsLAw4/UAAAAAbPmEwgEAAAAAAAAAAADY4j388MNp49NPP32DAe/PPvssbdyhQ4esepadX3a/nxQXF6e9SJ5tr7p168Zee+2VUS8AAAAAtk5C4QAAAAAAAAAAAABs0WbNmhXjxo1Lqw0ePHiD62bMmJE23m233bLqW3Z+2f1+UlBQEGvXri0d169fP5o1a7ZJegEAAACwdar8zx8CAAAAAAAAAAAAQMKNHDkybbzffvtF586dN7hu4cKFaeNdd901q7677LJL2riwsDCjPmXXVaVX2T2rauHChes99/qUffUcAAAAgE1PKBwAAAAAAAAAAACALVYqlYpHHnkkrTZo0KCM1i5fvjxt3LBhw6x6l51fXFwcq1evjrp161Zrn4rWlN2zqu69994YOnRotewFAAAAwKaTW9MHAAAAAAAAAAAAAICqev3112Pu3Lml4zp16sSAAQMyWls2WF2vXr2setevX3+De1ZHn4p6VVcoHAAAAIAtg1A4AAAAAAAAAAAAAFuskSNHpo2POeaYaNq0aUZrV61alTauU6dOVr3LvggeEbFy5cpq71NRr4r6AAAAALD1yqvpAwAAAAAAAAAAAABAVSxfvjyef/75tNqgQYMyXl/2xe41a9Zk1X/16tUb3LM6+lTUqyqvjVfkggsuiJNPPjmrNbNmzYr+/ftXS38AAAAAMiMUDgAAAAAAAAAAAMAW6ZlnnomioqLSccuWLePoo4/OeP12222XNi77oveGVPRad9k9q6NPRb0q6lMVLVq0iBYtWlTLXgAAAABsOrk1fQAAAAAAAAAAAAAAqIqHH344bXz66adHXl7mbyaVDVb/e8A8E2Xn5+XlVfiC98b2qWhNdYXCAQAAANgyCIUDAAAAAAAAAAAAsMUpKCiIt99+O602aNCgrPYo+0L2vHnzslo/f/78tHHz5s0z6lN2XVV6ed0bAAAAYNsiFA4AAAAAAAAAAADAFueRRx6JVCpVOt5vv/2ic+fOWe3Rrl27tPHcuXOzWl92fvv27Suc17p167QXzFeuXBmFhYWbpBcAAAAAWyehcAAAAAAAAAAAAAC2KKlUKh555JG02uDBg7Pep2yw+tNPP81q/WeffVbpfj+pXbt27LXXXlXutXr16igoKMioFwAAAABbJ6FwAAAAAAAAAAAAALYob775ZsyePbt0XKdOnRgwYEDW+3Tt2jVtPGnSpFi7dm3G68eNG1fpfpV99u6772bcZ/LkybF69erS8U477RQtWrTIeD0AAAAAWz6hcAAAAAAAAAAAAAC2KCNHjkwb9+vXL5o0aZL1Pu3bt097wbuoqCjjsHZRUVGMHz++dJyTkxPHHHPMeueX/eyVV17J+Jxl5/br1y/jtQAAAABsHYTCAQAAAAAAAAAAANhiFBUVxbPPPptWGzRoUJX3O/bYY9PGw4cPz2jdU089FcuXLy8d77///rHzzjuvd37fvn0jLy+vdDx27NgoKCjYYJ9UKhUPP/xwWu24447L6IwAAAAAbD2EwgEAAAAAAAAAAADYYjz33HNpYewdd9wxjjrqqCrvd9ZZZ0VOTk7p+Mknn4zPPvus0jWrVq2KW265Ja129tlnV7qmSZMm0b9//9JxKpWK/Pz8DZ7voYceijlz5pSOW7VqFUccccQG1wEAAACwdREKBwAAAAAAAAAAAGCLUfbV7NNPPz3tBe5sderUKU455ZTS8Zo1a2LgwIGxdOnSCuenUqm46KKL4vPPPy+ttW7dOs4666wN9ho6dGjk5v7vz3cfffTR+Pvf/77e+Z9++mlceumlabVrrrkm6tSps8FeAAAAAGxdhMIBAAAAAAAAAAAA2CJ8+eWXMXbs2LTaoEGDNnrfG264IRo0aFA6njRpUvTq1atcr5kzZ8ZJJ50U999/f1r9lltuidq1a2+wT4cOHeKcc85Jq51xxhlx7bXXxuLFi0trxcXF8fDDD8chhxwSS5YsKa136dIlBg4cmMU3AwAAAGBrUfU/iwgAAAAAAAAAAAAAm9EjjzwSqVSqdNytW7fo1KnTRu/bpk2bGD58eAwYMKB0/48//jj69OkTzZs3j9133z0WLlwY8+bNS+sfEfGHP/whTj755Ix7DRs2LD744IN4//33IyKipKQkrr/++rj11ltjzz33jLp160ZBQUEsX748bV2zZs3imWee2ahX0QEAAADYcrkVAgAAAAAAAAAAAGCLMHLkyLRxdbwS/pNTTz01UqlUnH322bFy5crSemFhYRQWFla45tJLL43bbrstqz4NGjSIl19+OU4++eR4/fXXS+tr1qyJGTNmVLhmjz32iNGjR0fbtm2z6gUAAADA1iO3pg8AAAAAAAAAAAAAABvyzjvvxBdffFE6rlOnTgwYMKBae5x22mkxderUGDBgQNSuXXu983r16hVjx46NP//5z5GTk5N1nyZNmsQrr7wSDzzwQLRp06bSeVdddVVMmTIlOnfunHUfAAAAALYeXgoHAAAAAAAAAAAAIPEOOeSQSKVSm7xP69at4/HHH4/77rsv3nnnnfj8889j2bJlUa9evdh9993j4IMPjl122WWj++Tm5sa5554b5557bkyZMiU++OCD+Oabb2LdunXRtGnT6NSpU3Tv3r3ScDoAAAAA2w6hcAAAAAAAAAAAAAAoY/vtt4++fftull6dO3f2EjgAAAAAlcqt6QMAAAAAAAAAAAAAAAAAAACwfkLhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJllfTBwC2fHtcMaba9ppzy6+rbS8AAAAAAAAAAACAylTnbyAj/A4SAAAA2HS8FA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAmWV9MHYPNYvnx5TJs2LaZPnx7fffddrFq1Kho1ahQtWrSI/fffP/bYY49q7zlt2rSYPHlyfPPNN7Fu3bpo2rRpdOrUKbp37x55edX3n96yZcti3LhxMXPmzFi6dGnUr18/WrVqFT179oydd9652voAAAAAAAAAAAAAAAAAAEBNEAqvYfPnz4+JEyfGhAkTYuLEifH+++/HsmXLSj9v1apVzJkzp0p7T5gwIUaNGhWvvfZaTJ48OUpKStY7t1WrVnHeeefFf/zHf0Tjxo2r1C8iIpVKxYgRI+LWW2+NmTNnVjinadOmcf7558cVV1wRDRs2rHKv2bNnx7XXXhtPP/10rFmzptznOTk5cdhhh8XQoUOjV69eVe4DAAAAAAAAAAAAAAAAAAA1SSi8BowbNy7uuOOOmDBhQnz99dfVvv9HH30UJ554YhQUFGS85ssvv4wrr7wy7r777hgxYkQcddRRWfddsmRJnHLKKfHKK69UOu+7776LG264IZ544okYPXp0dOzYMeteTz/9dAwePDhWrFix3jmpVCrGjh0bvXv3jssvvzxuvvnmyMnJyboXAAAAAAAAAAAAAAAAAADUpNyaPsC2aNKkSfHCCy9skkB4RMS8efPWGwjfYYcdol27dnHggQdG69aty4WkFyxYEL/+9a/jySefzKrnypUr48gjjywXCK9Tp060bds2OnfuXO5V8IKCgujTp0/MmjUrq17PPPNMnHbaaeUC4c2bN4/99tsvdt1117TvlUql4tZbb40hQ4Zk1QcAAAAAAAAAAAAAAAAAAJJAKDxhtttuu2rfs0ePHnHPPffEtGnTYsmSJTF9+vSYMGFCfPHFF/Htt9/GjTfeGA0aNCidX1JSEr/97W/jww8/zLjHkCFDYuLEiaXj3NzcuOaaa2LBggUxY8aM+OSTT+L777+PESNGROPGjUvnFRYWximnnBLr1q3LqM8XX3wRgwcPjpKSktLavvvuG6+//nosXLgwJk+eHF999VV89tlnccIJJ6Stveuuu+L555/P+DsBAAAAAAAAAAAAAAAAAEASCIXXoJ/97GfRu3fvuOyyy+KZZ56JOXPmxD//+c9q2Ts3NzfOOOOMmDp1aowfPz5+//vfR4cOHcrNa968eVx11VUxfvz4aNKkSWm9uLg4Lrrooox6TZ8+Pf72t7+l1R577LH405/+lBYAr1OnTgwaNCjefvvtaNSoUWn9ww8/jEceeSSjXtdcc00UFRWVjg844IB46623ok+fPmnz2rVrF88++2z87ne/S6tffvnlsXbt2ox6AQAAAAAAAAAAAAAAAABAEgiF14B+/fqVvtr9xhtvxG233RYnnXRStGrVqlr2b9u2bXzyySfx6KOPRseOHTNa06VLlxgxYkRa7a233opZs2ZtcO11112X9tL3mWeeGaeddtp653fs2DFuv/32tNrQoUOjuLi40j7Tpk2Lp556qnRcp06dGDlyZGy//fYVzs/JyYm777479t5779LaF198Ue57AgAAAAAAAAAAAAAAAABAkgmF14C99torOnToELm5m+Zff9u2bTMOg/+7Y489ttxr4i+99FKlaxYvXhzPP/986TgnJyfy8/M32Gvw4MFpIfgvv/wyXn311UrXPPTQQ1FSUlI6PvXUU2OfffapdE29evXiiiuuSKs9+OCDGzwfAAAAAAAAAAAAAAAAAAAkhVA4aQ499NC08dy5cyudP2bMmFi7dm3puHfv3tG6desN9snNzY3Bgwen1UaNGlXpmtGjR6eNzz777A32iYj4zW9+Ew0bNiwdT5o0Kb7++uuM1gIAAAAAAAAAAAAAAAAAQE0TCidN48aN08Y//PBDpfPHjBmTNv7Vr36Vca9f/vKXaeMXX3xxvXNnzJgRs2bNKh03bNgwevbsmVGfsnNTqVS5cwMAAAAAAAAAAAAAAAAAQFIJhZNm/vz5aeOmTZtWOv+jjz5KG2ca1I6I6NatW9StW7d0/PXXX0dhYWFGfQ488MDIy8vLuNfBBx9c6X4AAAAAAAAAAAAAAAAAAJBUQuGUSqVS8c4776TV2rZtu975xcXFaa93R0R06NAh435169aNvfbaK6322WefVTi3bD2bPhXNX18fAAAAAAAAAAAAAAAAAABIGqFwSo0dOzZmz55dOs7JyYmjjjpqvfMLCgpi7dq1peP69etHs2bNsuq52267pY1nzJhR4byy9bLrqqsPAAAAAAAAAAAAAAAAAAAkjVA4ERFRUlISV155ZVrtqKOOih133HG9axYuXJg23mWXXbLuW3ZN2T3XV9911103qk9hYWFW6wEAAAAAAAAAAAAAAAAAoKbk1fQBSIbbb789JkyYUDrOzc2NG2+8sdI1y5cvTxs3bNgw675l15Tds7p6lZ1fXFwcq1evjrp162a1T0UWLlyYdch81qxZG90XAAAAAAAAAAAAAAAAAIBtg1A48fbbb8fVV1+dVrvooovi5z//eaXryga169Wrl3Xv+vXrV7pndfUq2+enPasjFH7vvffG0KFDN3ofAAAAAAAAAAAAAAAAAACoSG5NH4CaVVBQECeccEKsXbu2tNa1a9e46aabNrh21apVaeM6depk3b9sKHvlypWbpFdF4e/19QIAAAAAAAAAAAAAAAAAgCQRCt+GLVq0KI4++uhYtGhRaa1ly5bx/PPPZ/SCdtnXutesWZP1GVavXl3pntXVq2yfynoBAAAAAAAAAAAAAAAAAECS5NX0AagZy5Yti6OPPjpmzpxZWtthhx3i5Zdfjj333DOjPbbbbru0cdnXvDNR9rXusntWV6+KXgVfX69sXXDBBXHyySdntWbWrFnRv3//aukPAAAAAAAAAAAAAAAAAMDWTSh8G7Rq1ao49thj4/333y+tNWjQIMaMGRP77rtvxvuUDVUXFRVlfZayazINhWfbq+z8vLy8anspvEWLFtGiRYtq2QsAAAAAAAAAAAAAAAAAAMrKrekDsHkVFxfHKaecEmPHji2t1alTJ55//vk4+OCDs9qrbBB6/vz5WZ+n7Jr1havL1ufNm7dRfZo3b57VegAAAAAAAAAAAAAAAAAAqClC4duQkpKS+O1vfxv//Oc/S2u1atWKJ554Io488sis92vdunXk5f3vY/MrV66MwsLCrPaYO3du2rh9+/YVzmvXrl2l66qrDwAAAAAAAAAAAAAAAAAAJI1Q+DYilUrF7373u3jyySdLazk5OfHggw/GiSeeWKU9a9euHXvttVda7dNPP814/erVq6OgoCCttr6wdtl6Nn0iIj777LOM+gAAAAAAAAAAAAAAAAAAQNIIhW8jLr744hg+fHha7T//8z9j0KBBG7Vv165d08bvvvtuxmsnT54cq1evLh3vtNNO0aJFi4z6TJo0KdauXZtxr3HjxlW6HwAAAAAAAAAAAAAAAAAAJJVQ+DbgmmuuibvvvjutdtNNN8WFF1640Xsfc8wxaeNXXnkl47Vl5/br12+9c9u3b5/2KnlRUVHGAfSioqIYP3586TgnJ6fcuQEAAAAAAAAAAAAAAAAAIKmEwrdyf/7zn+OGG25Iq1155ZVx5ZVXVsv+ffv2jby8vNLx2LFjo6CgYIPrUqlUPPzww2m14447rtI1xx57bNq47Mvn6/PUU0/F8uXLS8f7779/7LzzzhmtBQAAAAAAAAAAAAAAAACAmiYUvhW7//774/LLL0+rXXjhhXHTTTdVW48mTZpE//79S8epVCry8/M3uO6hhx6KOXPmlI5btWoVRxxxRKVrzjrrrMjJySkdP/nkk/HZZ59VumbVqlVxyy23pNXOPvvsDZ4PAAAAAAAAAAAAAAAAAACSQih8K/XEE0/EBRdckFYbPHhw/Od//me19xo6dGjk5v7vf0qPPvpo/P3vf1/v/E8//TQuvfTStNo111wTderUqbRPp06d4pRTTikdr1mzJgYOHBhLly6tcH4qlYqLLrooPv/889Ja69at46yzzqq0DwAAAAAAAAAAAAAAAAAAJEleTR9gWzVu3LhYuXJlufrHH3+cNl61alW8+uqrFe6x8847R4cOHcrVX3311Rg4cGCUlJSU1tq3bx+/+c1v4rXXXsvqnI0bN45u3bpVOqdDhw5xzjnnxAMPPFBaO+OMM+Kzzz6Liy++OBo3bhwREcXFxfH444/HkCFDYsmSJaVzu3TpEgMHDszoPDfccEP885//jBUrVkRExKRJk6JXr15x1113Re/evUvnzZw5M6688sp4/vnn09bfcsstUbt27Yx6AQAAAAAAAAAAAAAAAABAEgiF15DTTz89vvzyyw3O+/bbb+OXv/xlhZ8NHDgwHn744XL1d955J9auXZtWmz59ehx11FFZn/Owww6LsWPHbnDesGHD4oMPPoj3338/IiJKSkri+uuvj1tvvTX23HPPqFu3bhQUFMTy5cvT1jVr1iyeeeaZyMvL7D/FNm3axPDhw2PAgAGRSqUi4scgfZ8+faJ58+ax++67x8KFC2PevHmln//kD3/4Q5x88skZ9QEAAAAAAAAAAAAAAAAAgKQQCqdaNGjQIF5++eU4+eST4/XXXy+tr1mzJmbMmFHhmj322CNGjx4dbdu2zarXqaeeGqlUKs4+++y019YLCwujsLCwwjWXXnpp3HbbbVn1AQAAAAAAAAAAAAAAAACAJMit6QOw9WjSpEm88sor8cADD0SbNm0qnXfVVVfFlClTonPnzlXqddppp8XUqVNjwIABUbt27fXO69WrV4wdOzb+/Oc/R05OTpV6AQAAAAAAAAAAAAAAAABATfJSeA2ZM2fOJts7Pz8/8vPzN9n+lcnNzY1zzz03zj333JgyZUp88MEH8c0338S6deuiadOm0alTp+jevXulQe5MtW7dOh5//PG477774p133onPP/88li1bFvXq1Yvdd989Dj744Nhll12q4VsBAAAAAAAAAAAAAAAAAEDNEQpnk+ncuXOVXwLPxvbbbx99+/bd5H0AAAAAAAAAAAAAAAAAAKAm5Nb0AQAAAAAAAAAAAAAAAAAAAFg/oXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEy6vpAwAAAAAAkGxffPFFTJw4MebNmxdr1qyJxo0bR/v27aNnz55Rr169GjtXKpWKDz74ID766KNYuHBhRES0bNky9t1339hvv/0iJyenxs4GAAAAAAAAAAAA1UkoHAAAAACACo0aNSquv/76+OCDDyr8fLvttotBgwbFddddF82aNdts5youLo6777477rrrrpg/f36Fc3bddde46KKL4v/8n/8TtWvXrvYz3H///XHeeeeVq8+ePTv22GOPau8HAAAAAAAAAADAti23pg8AAAAAAECyrF69Os4444w4/vjj1xsIj4hYvnx53HPPPdGhQ4d46623NsvZvvrqq+jevXtcdtll6w2ER0TMmzcvLr300jjooIMqnVcV8+bNi8svv7xa9wQAAAAAAAD4/+zde3SW5bkn/ivhlEAoKGlwBwRCsQKOFbWWvcKYDcXzqOhQRDudLW7co2XctbseqKdBPAxVrIfaLa2Hau1Qj7XQQg+KFVFjsUXUXYNOEQINqAQklFMIkMwfv7XfX5+QwPtiII/x81nLtbzu977v63ps/3Lx9QYAgL0RCgcAAAAAIKOxsTEmTpwYs2fPTqx36tQpysrKYsSIEdGrV6/Eb7W1tXH66afHq6++ekBnW7duXYwZMyaWLl2aWC8sLIyjjjoqhg0bFgUFBYnflixZEmPGjIn169e32Rxf//rX469//Wub3QcAAAAAAAAAAAD7IhQOAAAAAEDGzJkzY+7cuYm1Sy+9NFavXh0rVqyIpUuXxkcffRTPPPNMDBgwILNn27Ztcd5558WmTZsO2GyTJk2K9957L1MXFBTE3XffHevXr48//elPUVVVFevXr48777wzEQ7/85//HP/0T//UJjP89Kc/jXnz5kVERI8ePdrkTgAAAAAAAAAAANgXoXAAAAAAACIiYsOGDXHrrbcm1mbMmBGzZs2K0tLSzFp+fn6ce+65UVlZGYMGDcqs19TUxJ133nlAZnv22Wfj17/+dabu0qVL/Pa3v43LL788unfvnlnv0aNH/Ou//mv85je/iS5dumTWf/nLX8YLL7zwsWZYv359XH755Zn6pptu+lj3AQAAAAAAAAAAQLaEwgEAAAAAiIiI22+/PTZv3pypKyoqYurUqa3u79evXzz44IOJtbvuuis2bNjQ5rPdcMMNifrb3/52VFRUtLr/H/7hH/aY/frrr/9YM3zjG9+I9evXR0TE8ccfnwiIAwAAAAAAAAAAwIEkFA4AAAAAQDQ2NsbDDz+cWLvxxhsjLy9vr+fGjh0bJ554YqbevHlzPPnkk20627//+7/Ha6+9lql79OgRV1111T7PXX311dGjR49MXVlZGcuWLduvGebNmxePPfZYRER06tQpHnjggejUqdN+3QUAAAAAAAAAAAC5EgoHAAAAACAqKyujtrY2Uw8ePDhGjx6d1dnJkycn6jlz5rThZBFz585N1Oedd1707Nlzn+d69uwZEyZMSKztz2x//etf4+tf/3qm/uY3vxnHHntszvcAAAAAAAAAAADA/hIKBwAAAAAg5s+fn6hPPvnkfb4S/rd7/9bChQtj69atB2y2U045JeuzzWebN29ezv2vvvrqqKmpiYiIQYMGxU033ZTzHQAAAAAAAAAAAPBxCIUDAAAAABBvvPFGoi4vL8/6bGlpaQwaNChTNzQ0RFVVVZvM1dTUFG+99dZ+zzZq1KhE/eabb0ZTU1PW51988cW4//77M/WsWbOie/fuWZ8HAAAAAAAAAACAtiAUDgAAAABALFu2LFEPHz48p/PN9ze/b3+tWrUqtm3blql79OgRAwYMyPr8wIEDEyHurVu3xl/+8peszm7fvj3++Z//ORMiv+CCC+K0007LujcAAAAAAAAAAAC0FaFwAAAAAIBPue3bt8fq1asTa4cffnhOdzTf/+67737suVq6J9e5WjqT7WzTpk2LP//5zxERceihh8bdd9+dc28AAAAAAAAAAABoC0LhAAAAAACfcuvXr8+8hh0R0aVLlygpKcnpjn79+iXqdevWtclsze/p379/znfsz2xLliyJO++8M1PPnDkz538mAAAAAAAAAAAA0FY6t/cAAAAAAAC0ry1btiTq7t27R15eXk539OjRY6937q/m9zTvk41cZ9u5c2dMnjw5du/eHRERo0ePjn/6p3/KuW9bWbduXdTW1uZ0Zvny5QdoGgAAAAAAAAAAANqDUDgAAAAAwKdc85B0QUFBzncUFhbu9c791R6z3XbbbfHmm29GRES3bt3ihz/8Yc4929J9990X06dPb9cZAAAAAAAAAAAAaF/57T0AAAAAAADtq76+PlF37do15zu6deuWqLdv3/6xZvoPB3u2ZcuWxS233JKpr7/++vj85z+fc08AAAAAAAAAAABoS0LhAAAAAACfcs1f325oaMj5jh07duz1zv11MGdrbGyMyZMnZ/YfddRRMXXq1Jz7AQAAAAAAAAAAQFvr3N4DAAAAAADQvoqKihJ189e5s9H89e3md+6vgznbvffeG6+++mpEROTl5cX9998fXbp0yblfW5syZUpMmDAhpzPLly+Pc84558AMBAAAAAAAAAAAwEEnFA4AAAAA8CnXPCS9bdu2aGpqiry8vKzv2Lp1617vbKvZmvfJRjazVVdXx3XXXZepL7300igvL8+514FQUlISJSUl7T0GAAAAAAAAAAAA7Si/vQcAAAAAAKB9FRcXJwLgO3fujHXr1uV0x5o1axJ1W4WYm99TU1OT8x3ZzHbjjTdmwuOlpaXxne98J+c+AAAAAAAAAAAAcKAIhQMAAAAAfMoVFhbGgAEDEmurV6/O6Y7m+4cOHfqx54qIOPLIIxP1X/7yl5zvaH6mpdnq6uoyf7927dro1atX5OXl7fOv5srKyhK/33333TnPCwAAAAAAAAAAAM0JhQMAAAAAsEdQuqqqKqfzy5Yt2+t9+2vgwIFRWFiYqbdu3RqrVq3K+vyqVati27ZtmbpHjx5x+OGHt8lsAAAAAAAAAAAAcLAIhQMAAAAAECNGjEjUlZWVWZ99//33o7q6OlN36dIlhg8f3iZz5eXlxRe+8IX9nu2VV15J1F/4whdafOEbAAAAAAAAAAAA0qxzew8AAAAAAED7O/PMM+O2227L1AsWLIimpqasAtTPPvtsoh4zZkwUFRW16WyLFy/O1M8991xccMEFWZ197rnnEvVZZ53V4r6bbropLrvsspxnO/nkkxP1//k//yf69u2bqY888sic7wQAAAAAAAAAAIDmhMIBAAAAAIjy8vIoLi6O9evXR0TEihUrYuHChTFmzJh9nn3ooYcS9bhx49p0trPPPjtuuOGGTP3UU0/F9773vX0Gzzdv3hxPPfVUVrM1f418f40aNSoGDRrUJncBAAAAAAAAAADAf8hv7wEAAAAAAGh/+fn5MWnSpMTa9OnTo6mpaa/nnn/++XjppZcydc+ePeO8885r09m+8IUvxAknnJCpt2zZErfffvs+z91+++2xdevWTP33f//3MXz48DadDQAAAAAAAAAAAA4GoXAAAAAAACIiYurUqYnXt1988cW47bbbWt2/Zs2auPjiixNrl19+eRQXF++1T15eXuKvhQsX7nO2m266KVF/5zvfiUWLFrW6v6XZb7nlln32AQAAAAAAAAAAgDQSCgcAAAAAICIiiouL49prr02sXXPNNTFlypRYu3ZtZq2xsTHmzJkT5eXlUV1dnVkvLS2NK6644oDMdtppp8Upp5ySqXfu3Bmnnnpq3HPPPbFt27bM+tatW+Puu++O0047LXbu3JlZP+OMM2Ls2LEHZDYAAAAAAAAAAAA40ITCAQAAAADImDp1apx55pmJtVmzZsWAAQPic5/7XBx33HHRp0+fOPfcc2P16tWZPYWFhfHkk09G7969D9hsjz76aJSVlWXq+vr6+OY3vxnFxcXxn/7Tf4qjjjoqiouL41//9V+jvr4+s+9zn/tcPPLIIwdsLgAAAAAAAAAAADjQhMIBAAAAAMjIz8+Pp556Ks4///zE+u7du2PFihWxdOnSqKurS/zWp0+f+NWvfhWjRo06oLP17ds3XnjhhTjmmGMS69u3b4+33347qqqqEmHwiIgRI0bECy+8EJ/97GcP6GwAAAAAAAAAAABwIAmFAwAAAACQUFBQEI899lg8/fTTMWLEiFb39ejRI6ZMmRJVVVUxevTogzLbwIED47XXXovbbrstSktLW91XWloat99+eyxevDgOP/zwgzIbAAAAAAAAAAAAHCid23sAAAAAAADSafz48TF+/PhYvnx5LF68ONasWRMNDQ3Ru3fvGDZsWIwaNSoKCgpyvrepqeljzdW1a9e4+uqr48orr4wlS5bEm2++GevWrYuIiJKSkhgxYkQcd9xxkZ9/4P+7qB/3WwAAAAAAAAAAACAbQuEAAAAAAOzVkCFDYsiQIe09xh7y8/PjhBNOiBNOOKG9RwEAAAAAAAAAAIAD6sA/kwIAAAAAAAAAAAAAAAAAAMB+EwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBTr3N4DAAAAAAAAAAAAAMD+ePfdd+PNN9+Mmpqa2LZtWxQWFkbfvn3j85//fBxzzDHRrVu3/b67vr4+Kisr45133omNGzdG165do3///jFy5MgYPHhwG35FxHvvvRevvfZa1NTURENDQxxyyCExdOjQKC8vj4KCgjbtBQAAAMAnk1A4AAAAAAAAAAAAAJ8YmzdvjnvvvTcefPDBWLlyZav7unbtGl/60pfiK1/5Slx++eVZ319bWxvTp0+PRx55JLZu3drinuOPPz5uuOGGGDduXM7z/605c+bEzTffHK+//nqLvxcVFcWkSZNi2rRpUVxc/LF6AQAAAPDJlt/eAwAAAAAAAAAAAABANubNmxdHHHFEXHfddXsNhEdENDQ0xMsvvxwzZszI+v6FCxfG8OHD49/+7d9aDYRHRCxZsiTOOeecuPDCC6OhoSHr+//Djh074mtf+1qce+65rQbCIyK2bNkS3//+92P48OGxaNGinPsAAAAA0HEIhQMAAAAAAAAAAACQenfddVecffbZ8eGHHybWCwoKYvDgwfGlL30pjj766P1+Ufvll1+OM844I9avX59Y7927dxx77LExaNCg6NSpU+K3Rx99NC644IJoamrKuk9jY2NMnDgxZs+enVjv1KlTlJWVxYgRI6JXr16J32pra+P000+PV199NcevAgAAAKCjEAoHAAAAAAAAAAAAINUeeuih+Na3vpUIX59++unx61//Ourq6uK9996LxYsXx1tvvRW1tbWxZs2a+MlPfhLjx4+Prl277vP+jRs3xsSJE2P79u2ZtYEDB8acOXPio48+itdffz1WrlwZ1dXVcckllyTOPvPMM3HXXXdl/S0zZ86MuXPnJtYuvfTSWL16daxYsSKWLl0aH330UTzzzDMxYMCAzJ5t27bFeeedF5s2bcq6FwAAAAAdh1A4AAAAAAAAAAAAAKm1fPnyuOyyyzJ1ly5d4qc//Wn86le/itNOOy26deu2x5nS0tL42te+Fk8//XS8+eab++wxc+bMWLt2baYuKyuLysrKGDduXOTl5WXW+/fvHz/4wQ/i1ltvTZy/6aabYuPGjfvss2HDhj3OzpgxI2bNmhWlpaWZtfz8/Dj33HOjsrIyBg0alFmvqamJO++8c599AAAAAOh4hMIBAAAAAAAAAAAASK3/8T/+R9TX12fq2bNnxwUXXJD1+UMOOWSvv9fW1sa9996bWHvggQcSIe3mrrnmmqioqMjUmzZtijvuuGOfs9x+++2xefPmTF1RURFTp05tdX+/fv3iwQcfTKzdddddsWHDhn32AgAAAKBjEQoHAAAAAAAAAAAAIJXmzp0bL7zwQqaeMGFCTJgwoU17PP7447Fly5ZMXVFREWPHjt3rmby8vJg2bVpi7Uc/+lE0NTW1eqaxsTEefvjhxNqNN96YeIm8JWPHjo0TTzwxU2/evDmefPLJvZ4BAAAAoOMRCgcAAAAAAAAAAAAgle6///5E3TyI3Rbmzp2bqCdPnpzVuTFjxkRZWVmm/uCDD+L3v/99q/srKyujtrY2Uw8ePDhGjx6dVa/mM82ZMyercwAAAAB0HELhAAAAAAAAAAAAAKTOmjVr4re//W2mHjFiRBx11FFt2mPLli2xaNGixNopp5yS1dm8vLw46aSTEmvz5s1rdf/8+fMT9cknn7zPV8L/du/fWrhwYWzdujWrswAAAAB0DELhAAAAAAAAAAAAAKTOb37zm9i9e3emHjNmTJv3ePvtt2Pnzp2ZuqysLA477LCsz48aNSpRv/HGG63ubf5beXl51n1KS0tj0KBBmbqhoSGqqqqyPg8AAADAJ59QOAAAAAAAAAAAAACp84c//CFRH3PMMZm/X7p0aXzjG9+IY445Jg455JDo3r17DBo0KE4++eS44447Ys2aNVn1WLZsWaIePnx4TjM239/8vvbqBQAAAEDHIxQOAAAAAAAAAAAAQOo0D4UPHjw4tmzZEpMnT47jjjsu7r333njrrbeirq4utm/fHqtWrYoFCxbEVVddFUcccURce+21iVfAW/Luu+8m6sMPPzynGZvvX7VqVdTX1++xb/v27bF69eo27dV8dgAAAAA6ts7tPQAAAAAAAAAAAAAANLd8+fJEnZ+fHxUVFbF06dJ9nt2+fXvMmDEj/vCHP8QzzzwTPXv2bHHfunXrEnX//v1zmrFv377RuXPn2LVrV0RENDY2xoYNG6Jfv36JfevXr4+mpqZM3aVLlygpKcmpV/M7m8++v9atWxe1tbU5nWn+vw0AAAAAB55QOAAAAAAAAAAAAACp0tjYGJs3b06sfeMb38gEwvPy8uLMM8+MM844I/r37x9bt26NpUuXxk9+8pNYu3Zt5syCBQti0qRJ8bOf/azFPlu2bEnUPXr0yGnOvLy8KCwsTMza/M6W1rp37x55eXk59Wo+W0t99sd9990X06dPb5O7AAAAADhwhMIBAAAAAAAAAAAASJVNmzYlXtaOiHj99dcjIqJPnz7x85//PE488cTE7xMnTozrr78+LrnkkvjpT3+aWX/mmWfi0UcfjX/8x3/co0/zYHVBQUHOs+5PKHx/++ztTgAAAAA6tvz2HgAAAAAAAAAAAAAA/lZrgedOnTrF/Pnz9wiE/4eioqL4yU9+Eqecckpi/X//7/+9R8g8IqK+vj5Rd+3aNedZu3Xrlqi3b9/ebn0AAAAA6Li8FA4AAAAAAAAAAABAqrT2kvbFF18cI0eO3OvZ/Pz8mDVrVhxxxBHR2NgYERHvvvtuvPjiizF69Oi99mloaMh51h07duz1zoPZZ39MmTIlJkyYkNOZ5cuXxznnnNMm/QEAAADIjlA4AAAAAAAAAAAAAKlSVFTU4vo///M/Z3V+8ODBcdJJJ8Wzzz6bWWspFN68T/MXvbPR/MXulmY/WH32R0lJSZSUlLTJXQAAAAAcOPntPQAAAAAAAAAAAAAA/K3CwsLo1KlTYq1nz55x7LHHZn3HP/zDPyTqP/7xj3vsaR6s3rp1aw5TRjQ1Ne1XKHzbtm3R1NSUU6/ms7VVKBwAAACATwahcAAAAAAAAAAAAABSp/nr1UOGDIn8/Oz/6OuRRx6ZqNetW7fPHjU1NTlMGPHhhx/Grl27MnV+fn4UFxfvsa+4uDjy8vIy9c6dO1ucZ2/WrFmTqL3uDQAAAPDpIhQOAAAAAAAAAAAAQOoMGzYsUX/mM5/J6Xzz/Rs3btxjT/Pg+OrVq3Pq0Xz/wIEDo6CgYI99hYWFMWDAgDbtNXTo0JzOAwAAAPDJJhQOAAAAAAAAAAAAQOoMHz48Ue/YsSOn8/X19Ym6e/fue+xpHqyuqqrKqceyZcv2el979QIAAACg4xEKBwAAAAAAAAAAACB1jjvuuET94Ycf5nR+3bp1ibpPnz577DnqqKOiS5cumbq6ujref//9rHu88soriXrEiBGt7m3+W2VlZdZ93n///aiurs7UXbp02SM0DwAAAEDHJhQOAAAAAAAAAAAAQOr8l//yXyI/////o64rV66Mjz76KOvzS5YsSdRHHnnkHnt69uwZFRUVibXnnnsuq/ubmppiwYIFibWzzjqr1f1nnnlmol6wYEE0NTVl1evZZ59N1GPGjImioqKszgIAAADQMQiFAwAAAAAAAAAAAJA6JSUlMWrUqMTaM888k9XZXbt2xc9//vPE2ujRo1vce/bZZyfqhx56KKseL7zwQqxcuTJT9+3bN0aOHNnq/vLy8iguLs7UK1asiIULF2bVq/lM48aNy+ocAAAAAB2HUDgAAAAAAAAAAAAAqXTJJZck6pkzZ8aOHTv2ee6BBx6IDz74IFN/5jOfiVNPPbXFveeff3706NEjUy9atCh+97vf7fX+pqammD59emLtoosuSrxs3lx+fn5MmjQpsTZ9+vR9vhb+/PPPx0svvZSpe/bsGeedd95ezwAAAADQ8QiFAwAAAAAAAAAAAJBKF1xwQRx99NGZ+v/+3/8bl1xySTQ2NrZ6ZvHixXH11Vcn1qZMmRK9evVqcX9JSUlcdtllibWLL7441q5d22qPGTNmxKJFizJ1r1694qqrrtrrt0RETJ06NYqKijL1iy++GLfddlur+9esWRMXX3xxYu3yyy9PvDgOAAAAwKeDUDgAAAAAAAAAAAAAqZSfnx933XVX5OXlZdZ+/OMfx6mnnhpLlixJ7N20aVPceeedcdJJJ8WWLVsy65///Ofj2muv3Wufq6++Og477LBMvXLlyigvL49f/OIXiZe8a2pq4tJLL43rrrsucf66666LQw89dJ/fU1xcvMcs11xzTUyZMiURQm9sbIw5c+ZEeXl5VFdXZ9ZLS0vjiiuu2GcfAAAAADqezu09AAAAAAAAAAAAAAC0ZuzYsTFjxoz49re/nVlbsGBBfPGLX4zDDjss+vfvH1u3bo333nsvGhoaEmf79OkTTz/9dPTs2XOvPQ499NB44okn4tRTT436+vqIiFi1alWMGzcuevfuHWVlZVFXVxerV6+O3bt3J86OGzcurrzyyqy/Z+rUqVFZWRnz5s3LrM2aNSvuv//+GDhwYPTq1StWrlwZdXV1iXOFhYXx5JNPRu/evbPuBQAAAEDH4aVwAAAAAAAAAAAAAFJt6tSp8b3vfS+6dOmSWP/ggw/ij3/8YyxbtmyPQPiRRx4Zr776ahx99NFZ9aioqIj58+fv8eJ3XV1dLF26NFauXLlHIPyrX/1qPPHEE4mXzPclPz8/nnrqqTj//PMT67t3744VK1bE0qVL9wiE9+nTJ371q1/FqFGjsu4DAAAAQMciFA4AAAAAAAAAAABA6v3Lv/xLvPXWWzFx4sQ9wuF/q6ysLO65555466234ogjjsipx5e//OWoqqqKr3/969G9e/dW9x177LHxs5/9LGbPnh3dunXLqUdEREFBQTz22GPx9NNPx4gRI1rd16NHj5gyZUpUVVXF6NGjc+4DAAAAQMfRub0HAAAAAAAAAAAAAIBsDB06NB5//PH461//GpWVlfHnP/85Nm3aFEVFRdG3b9847rjj4sgjj/xYPfr27Rv33XdffPe7343KyspYtmxZ1NXVRdeuXaNfv34xcuTIGDJkSJt8z/jx42P8+PGxfPnyWLx4caxZsyYaGhqid+/eMWzYsBg1alQUFBS0SS8AAAAAPtmEwgEAAAAAAAAAAAD4RPnMZz4Tp512Wpx22mkHrEdhYWGMHTs2xo4de8B6/IchQ4a0WdAcAAAAgI4pv70HAAAAAAAAAAAAAAAAAAAAoHVC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKda5vQfg4Kqvr4/Kysp45513YuPGjdG1a9fo379/jBw5MgYPHtymvd5777147bXXoqamJhoaGuKQQw6JoUOHRnl5eRQUFLRZn4P5TQAAAAAAAAAAAAAAAAAAcLAJhbezNWvWxGuvvRaLFy+O1157Lf74xz/G5s2bM78PHDgwqqurP3af2tramD59ejzyyCOxdevWFvccf/zxccMNN8S4ceM+Vq85c+bEzTffHK+//nqLvxcVFcWkSZNi2rRpUVxcvN99DuY3AQAAAAAAAAAAAAAAAABAexEKbwevvPJKfPe7343FixfH2rVrD3i/hQsXxoQJE2L9+vV73bdkyZI455xz4h//8R/jgQceiK5du+bUZ8eOHTF58uSYPXv2Xvdt2bIlvv/978cTTzwRTz/9dFRUVOTUJ+LgfRMAAAAAAAAAAAAAAAAAALS3/PYe4NPoD3/4Q/z85z8/KIHwl19+Oc4444w9wtO9e/eOY489NgYNGhSdOnVK/Pboo4/GBRdcEE1NTVn3aWxsjIkTJ+4RCO/UqVOUlZXFiBEjolevXonfamtr4/TTT49XX301ld8EAAAAAAAAAAAAAAAAAABpIBSeMkVFRW1218aNG2PixImxffv2zNrAgQNjzpw58dFHH8Xrr78eK1eujOrq6rjkkksSZ5955pm46667su41c+bMmDt3bmLt0ksvjdWrV8eKFSti6dKl8dFHH8UzzzwTAwYMyOzZtm1bnHfeebFp06bUfRMAAAAAAAAAAAAAAAAAAKSBUHg76tmzZ4wePTquuuqqeOqpp6K6ujp++ctfttn9M2fOTLxGXlZWFpWVlTFu3LjIy8vLrPfv3z9+8IMfxK233po4f9NNN8XGjRv32WfDhg17nJ0xY0bMmjUrSktLM2v5+flx7rnnRmVlZQwaNCizXlNTE3feeWeqvgkAAAAAAAAAAAAAAAAAANJCKLwdnHXWWfH2229HXV1dvPDCC3H77bfHV77ylRg4cGCb9aitrY177703sfbAAw8kQtrNXXPNNVFRUZGpN23aFHfcccc+e91+++2xefPmTF1RURFTp05tdX+/fv3iwQcfTKzdddddsWHDhr32OZjfBAAAAAAAAAAAAAAAAAAAaSEU3g4+97nPxfDhwyM//8D943/88cdjy5YtmbqioiLGjh271zN5eXkxbdq0xNqPfvSjaGpqavVMY2NjPPzww4m1G2+8MfFqd0vGjh0bJ554YqbevHlzPPnkk3s9c7C+CQAAAAAAAAAAAAAAAAAA0kQovIOaO3duop48eXJW58aMGRNlZWWZ+oMPPojf//73re6vrKyM2traTD148OAYPXp0Vr2azzRnzpy97j9Y3wQAAAAAAAAAAAAAAAAAAGkiFN4BbdmyJRYtWpRYO+WUU7I6m5eXFyeddFJibd68ea3unz9/fqI++eST9/lK+N/u/VsLFy6MrVu3trj3YH4TAAAAAAAAAAAAAAAAAACkiVB4B/T222/Hzp07M3VZWVkcdthhWZ8fNWpUon7jjTda3dv8t/Ly8qz7lJaWxqBBgzJ1Q0NDVFVVtbj3YH4TAAAAAAAAAAAAAAAAAACkiVB4B7Rs2bJEPXz48JzON9/f/L726HUwvwkAAAAAAAAAAAAAAAAAANJEKLwDevfddxP14YcfntP55vtXrVoV9fX1e+zbvn17rF69uk17NZ+9tfUD9U0AAAAAAAAAAAAAAAAAAJA2ndt7ANreunXrEnX//v1zOt+3b9/o3Llz7Nq1KyIiGhsbY8OGDdGvX7/EvvXr10dTU1Om7tKlS5SUlOTUq/mdzWdvbf1AfdP+WLduXdTW1uZ0Zvny5R+7LwAAAAAAAAAAAAAAAAAAnw5C4R3Qli1bEnWPHj1yOp+XlxeFhYWxefPmVu9saa179+6Rl5eXU6/ms7XUp6X1A/VN++O+++6L6dOnt8ldAAAAAAAAAAAAAAAAAADQXH57D0Dbax52LigoyPmOwsLCvd55MPsc7F4AAAAAAAAAAAAAAAAAAJAmQuEdUH19faLu2rVrznd069YtUW/fvr3d+hzsXgAAAAAAAAAAAAAAAAAAkCad23sA2l7zV7QbGhpyvmPHjh17vfNg9jnYvXI1ZcqUmDBhQk5nli9fHuecc06b9AcAAAAAAAAAAAAAAAAAoGMTCu+AioqKEnXzV7az0fwV7eZ3Hsw+B7tXrkpKSqKkpKRN7gIAAAAAAAAAAAAAAAAAgOby23sA2l7zsPPWrVtzOt/U1LRfofBt27ZFU1NTTr2az5ZtKPxAfRMAAAAAAAAAAAAAAAAAAKSNUHgH1PzV6pqampzOf/jhh7Fr165MnZ+fH8XFxXvsKy4ujry8vEy9c+fOWLduXU691qxZk6hbe3H7YH0TAAAAAAAAAAAAAAAAAACkjVB4B3TkkUcm6tWrV+d0vvn+gQMHRkFBwR77CgsLY8CAAW3aa+jQoS3uO1jfBAAAAAAAAAAAAAAAAAAAaSMU3gE1D1ZXVVXldH7ZsmV7va89eh3MbwIAAAAAAAAAAAAAAAAAgDQRCu+AjjrqqOjSpUumrq6ujvfffz/r86+88kqiHjFiRKt7m/9WWVmZdZ/3338/qqurM3WXLl1i+PDhLe49mN8EAAAAAAAAAAAAAAAAAABpIhTeAfXs2TMqKioSa88991xWZ5uammLBggWJtbPOOqvV/WeeeWaiXrBgQTQ1NWXV69lnn03UY8aMiaKiohb3HsxvAgAAAAAAAAAAAAAAAACANBEK76DOPvvsRP3QQw9lde6FF16IlStXZuq+ffvGyJEjW91fXl4excXFmXrFihWxcOHCrHo1n2ncuHF73X+wvgkAAAAAAAAAAAAAAAAAANJEKLyDOv/886NHjx6ZetGiRfG73/1ur2eamppi+vTpibWLLroo8vNb/79Jfn5+TJo0KbE2ffr0fb4W/vzzz8dLL72UqXv27BnnnXfeXs8crG8CAAAAAAAAAAAAAAAAAIA0kYztoEpKSuKyyy5LrF188cWxdu3aVs/MmDEjFi1alKl79eoVV1111T57TZ06NYqKijL1iy++GLfddlur+9esWRMXX3xxYu3yyy9PvDjekoP5TQAAAAAAAAAAAAAAAAAAkBad23uAT6tXXnkltm/fvsf6m2++majr6+tjwYIFLd5RWloaw4cPb7XH1VdfHT/+8Y/jgw8+iIiIlStXRnl5eXzve9+Ls846K/Ly8iIioqamJm655Zb44Q9/mDh/3XXXxaGHHrrPbykuLo5rr702rr322szaNddcE6tXr47rr78+SktLIyKisbExfvGLX8Tll18eq1evTnzHFVdcsc8+B/ObAAAAAAAAAAAAAAAAAAAgLYTC28l/+2//LVatWrXPfR9++GGcfPLJLf524YUXxiOPPNLq2UMPPTSeeOKJOPXUU6O+vj4iIlatWhXjxo2L3r17R1lZWdTV1cXq1atj9+7dibPjxo2LK6+8MuvvmTp1alRWVsa8efMya7NmzYr7778/Bg4cGL169YqVK1dGXV1d4lxhYWE8+eST0bt376z6HMxvAgAAAAAAAAAAAAAAAACANMhv7wE4sCoqKmL+/Pl7vI5dV1cXS5cujZUrV+4Rnv7qV78aTzzxRObV7Wzk5+fHU089Feeff35ifffu3bFixYpYunTpHoHwPn36xK9+9asYNWpUKr8JAAAAAAAAAAAAAAAAAADSQCj8U+DLX/5yVFVVxde//vXo3r17q/uOPfbY+NnPfhazZ8+Obt265dynoKAgHnvssXj66adjxIgRre7r0aNHTJkyJaqqqmL06NE594k4eN8EAAAAAAAAAAAAAAAAAADtrXN7D/BpVV1dfVD79e3bN+6777747ne/G5WVlbFs2bKoq6uLrl27Rr9+/WLkyJExZMiQNuk1fvz4GD9+fCxfvjwWL14ca9asiYaGhujdu3cMGzYsRo0aFQUFBR+7z8H8JgAAAAAAAAAAAAAAAAAAaC9C4Z8yhYWFMXbs2Bg7duwB7zVkyJCDEso+mN8EAAAAAAAAAAAAAAAAAAAHW357DwAAAAAAAAAAAAAAAAAAAEDrhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAFlneQcAAQAASURBVAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFKsc3sPAAAAAAAAAAAAAABpUl9fH5WVlfHOO+/Exo0bo2vXrtG/f/8YOXJkDB48uE17vffee/Haa69FTU1NNDQ0xCGHHBJDhw6N8vLyKCgoaNNeAAAAAHxyCYUDAAAAAAAAAAAAkDo33nhjTJ8+fb/PX3jhhfHII4/kdKa2tjamT58ejzzySGzdurXFPccff3zccMMNMW7cuP2eLSJizpw5cfPNN8frr7/e4u9FRUUxadKkmDZtWhQXF3+sXgAAAAB88uW39wAAAAAAAAAAAAAA0N4WLlwYw4cPj3/7t39rNRAeEbFkyZI455xz4sILL4yGhoac++zYsSO+9rWvxbnnnttqIDwiYsuWLfH9738/hg8fHosWLcq5DwAAAAAdi1A4AAAAAAAAAAAAAJ9qL7/8cpxxxhmxfv36xHrv3r3j2GOPjUGDBkWnTp0Svz366KNxwQUXRFNTU9Z9GhsbY+LEiTF79uzEeqdOnaKsrCxGjBgRvXr1SvxWW1sbp59+erz66qs5fhUAAAAAHUnn9h4AAAAAAAAAAAAAAPbljjvuiGOOOSbr/aWlpVnt27hxY0ycODG2b9+eWRs4cGDcc889cfbZZ0deXl5ERNTU1MQtt9wSP/zhDzP7nnnmmbjrrrviW9/6Vla9Zs6cGXPnzk2sXXrppXHDDTdk5m1sbIy5c+fGN7/5zVi9enVERGzbti3OO++8+NOf/rRHaBwAAACATwehcAAAAAAAAAAAAABS7/jjj4/Ro0e3+b0zZ86MtWvXZuqysrJ4+eWX9wiV9+/fP37wgx/EgAED4rrrrsus33TTTXHRRRfFIYccstc+GzZsiFtvvTWxNmPGjPj2t7+dWMvPz49zzz03vvSlL8V//s//OaqrqyPi/wul33nnnTF9+vT9+UwAAAAAPuHy23sAAAAAAAAAAAAAAGgPtbW1ce+99ybWHnjggb2+Mn7NNddERUVFpt60aVPccccd++x1++23x+bNmzN1RUVFTJ06tdX9/fr1iwcffDCxdtddd8WGDRv22QsAAACAjkcoHAAAAAAAAAAAAIBPpccffzy2bNmSqSsqKmLs2LF7PZOXlxfTpk1LrP3oRz+KpqamVs80NjbGww8/nFi78cYbIy8vb6+9xo4dGyeeeGKm3rx5czz55JN7PQMAAABAxyQUDgAAAAAAAAAAAMCn0ty5cxP15MmTszo3ZsyYKCsry9QffPBB/P73v291f2VlZdTW1mbqwYMHx+jRo7Pq1XymOXPmZHUOAAAAgI5FKBwAAAAAAAAAAACAT50tW7bEokWLEmunnHJKVmfz8vLipJNOSqzNmzev1f3z589P1CeffPI+Xwn/271/a+HChbF169aszgIAAADQcQiFAwAAAAAAAAAAAPCp8/bbb8fOnTszdVlZWRx22GFZnx81alSifuONN1rd2/y38vLyrPuUlpbGoEGDMnVDQ0NUVVVlfR4AAACAjqFzew8AAAAAAAAAAAAAANnYsWNHrFixIjZs2BBdunSJPn36RGlpaXTv3j3nu5YtW5aohw8fntP55vub39fWvaqrqxP3nXDCCTndAQAAAMAnm1A4AAAAAAAAAAAAAKn3P//n/4wVK1ZEfX19Yr1z585x/PHHx+mnnx5TpkyJz372s1nd9+677ybqww8/PKd5mu9ftWpV1NfXR0FBQWJ9+/btsXr16jbt1Xx2AAAAADo+oXAAAAAAAAAAAAAAUq+qqqrF9V27dsXixYtj8eLFcdttt8WVV14Z06ZNi06dOu31vnXr1iXq/v375zRP3759o3PnzrFr166IiGhsbIwNGzZEv379EvvWr18fTU1NmbpLly5RUlKSU6/mdzaf/eNYt25d1NbW5nRm+fLlbdYfAAAAgOwIhQMAAAAAAAAAAADQIWzfvj1uvvnmeOmll+KXv/xlFBUVtbp3y5YtibpHjx459crLy4vCwsLYvHlzq3e2tNa9e/fIy8vLqVfz2Vrqs7/uu+++mD59epvdBwAAAMCBkd/eAwAAAAAAAAAAAABAS/Ly8qK8vDxuvfXWeO6556Kmpia2bdsW9fX1sWbNmvjlL38Zl1xySRQUFCTOLVy4MM4///zYvXt3q3c3D1Y3vyMbhYWFe73zYPYBAAAAoGMTCgcAAAAAAAAAAAAgdU455ZR455134pVXXolrr702TjrppOjXr18UFhZGt27dorS0NM4888z4wQ9+EH/+859j1KhRifPz58+P++67r9X76+vrE3XXrl1znrFbt26Jevv27e3WBwAAAICOrXN7DwAAAAAAAAAAAAAAzZWXl2e9t3///rFgwYL48pe/HK+++mpm/ZZbbonJkydH9+7d9zjT/MXuhoaGnGfcsWPHXu88mH3215QpU2LChAk5nVm+fHmcc845bTYDAAAAAPsmFA4AAAAAAAAAAADAJ15BQUE8+uijMWzYsNi1a1dERKxbty6effbZFgPMRUVFibr5i97ZaP5id/M7D2af/VVSUhIlJSVtdh8AAAAAB0Z+ew8AAAAAAAAAAAAAAG1hyJAhcfbZZyfWnn322Rb3Ng9Wb926NadeTU1N+xUK37ZtWzQ1NeXUq/lsbRkKBwAAAOCTQSgcAAAAAAAAAAAAgA5j7Nixifrdd99tcV/z17Frampy6vPhhx9mXiSPiMjPz4/i4uI99hUXF0deXl6m3rlzZ6xbty6nXmvWrEnUXvYGAAAA+PQRCgcAAAAAAAAAAACgwzj88MMTdW1tbYv7jjzyyES9evXqnPo03z9w4MAoKCjYY19hYWEMGDCgTXsNHTo0p/MAAAAAfPIJhQMAAAAAAAAAAADQYXTp0iVR79y5s8V9zYPVVVVVOfVZtmzZXu9rr14AAAAAdExC4QAAAAAAAAAAAAB0GB988EGi/uxnP9vivqOOOioRIK+uro73338/6z6vvPJKoh4xYkSre5v/VllZmXWf999/P6qrqzN1ly5dYvjw4VmfBwAAAKBjEAoHAAAAAAAAAAAAoMN4+eWXE/Xhhx/e4r6ePXtGRUVFYu25557LqkdTU1MsWLAgsXbWWWe1uv/MM89M1AsWLIimpqasej377LOJesyYMVFUVJTVWQAAAAA6DqFwAAAAAAAAAAAAADqEurq6+NnPfpZYGzt2bKv7zz777ET90EMPZdXnhRdeiJUrV2bqvn37xsiRI1vdX15eHsXFxZl6xYoVsXDhwqx6NZ9p3LhxWZ0DAAAAoGMRCgcAAAAAAAAAAACgQ7jyyiujrq4uU3ft2jVOP/30Vveff/750aNHj0y9aNGi+N3vfrfXHk1NTTF9+vTE2kUXXRT5+a3/sdz8/PyYNGlSYm369On7fC38+eefj5deeilT9+zZM84777y9ngEAAACgYxIKBwAAAAAAAAAAACBVvvOd78SSJUuy3r9r16644oor9nhV+9JLL42/+7u/a/VcSUlJXHbZZYm1iy++ONauXdvqmRkzZsSiRYsyda9eveKqq67a54xTp06NoqKiTP3iiy/Gbbfd1ur+NWvWxMUXX5xYu/zyyxMvjgMAAADw6SEUDgAAAAAAAAAAAECq/OY3v4kvfvGLMWrUqLjnnnviT3/6U+zatWuPfZs2bYrHHnssTjjhhLjzzjsTv33uc5+L//W//tc+e1199dVx2GGHZeqVK1dGeXl5/OIXv0i85F1TUxOXXnppXHfddYnz1113XRx66KH77FNcXBzXXnttYu2aa66JKVOmJELojY2NMWfOnCgvL4/q6urMemlpaVxxxRX77AMAAABAx9S5vQcAAAAAAAAAAAAAgJZUVlZGZWVlRER069Yt+vfvH7169YpOnTrFhg0borq6OhobG/c4d9hhh8Wvf/3r6NOnzz57HHroofHEE0/EqaeeGvX19RERsWrVqhg3blz07t07ysrKoq6uLlavXh27d+9OnB03blxceeWVWX/P1KlTo7KyMubNm5dZmzVrVtx///0xcODA6NWrV6xcuTLq6uoS5woLC+PJJ5+M3r17Z90LAAAAgI5FKBwAAAAAAAAAAACA1NuxY0e89957+9x3xhlnxMMPPxwlJSVZ311RURHz58+PCRMmxEcffZRZr6uri6VLl7Z45qtf/Wr86Ec/iry8vKz75Ofnx1NPPRUXXXRRPP7445n13bt3x4oVK1o806dPn3j66adj1KhRWfcBAAAAoOMRCgcAAAAAYK/ee++9eO2116KmpiYaGhrikEMOiaFDh0Z5eXkUFBS021xNTU3x+uuvxxtvvBHr1q2LiIi+ffvGMcccE8cdd1xOfxCzNbW1tfHv//7v8d5778XGjRujqakpDjnkkOjfv3/8/d//fRx66KEfuwcAAAAAsKfrrrsuhg0bFi+99FK88847e7zQ3VxRUVGcfvrpcdlll0VFRcV+9fzyl78cVVVVMX369Pjxj38c27Zta3HfscceG9dff3381//6X/erT0FBQTz22GPxla98JW655ZZ44403WtzXo0ePuPDCC2PatGk5BdwBAAAA6JiEwgEAAAAAaNGcOXPi5ptvjtdff73F34uKimLSpEkxbdq0KC4uPmhz7dy5M+655564++67Y82aNS3u6d+/f3zzm9+Mb3zjG9GlS5es725oaIjf/va3MX/+/Hj++edj+fLlre7Ny8uLE044If7lX/4lzj///Ojc2b9yBwAAAIC2cvLJJ8fJJ58cERHbtm2LqqqqqK6ujvfffz+2bNkSjY2N0bt37zjkkENi+PDhcfTRR0enTp0+dt++ffvGfffdF9/97nejsrIyli1bFnV1ddG1a9fo169fjBw5MoYMGfKx+0REjB8/PsaPHx/Lly+PxYsXx5o1a6KhoSF69+4dw4YNi1GjRrXrf5gTAAAAgHTxJ9QAAAAAAEjYsWNHTJ48OWbPnr3XfVu2bInvf//78cQTT8TTTz+936/v5OIvf/lLjBs3LpYuXbrXfTU1NXHllVfGY489FnPnzo1+/frt8+5HHnkkvvWtb8XGjRuzmqWpqSlee+21+O///b/H9773vZg9e3YcccQRWZ0FAAAAALLXvXv3+OIXvxhf/OIXD1rPwsLCGDt2bIwdO/aA9xoyZEibBc0BAAAA6Ljy23sAAAAAAADSo7GxMSZOnLhHILxTp05RVlYWI0aMiF69eiV+q62tjdNPPz1effXVAzrbunXrYsyYMXsEwgsLC+Ooo46KYcOG7fFqzpIlS2LMmDGxfv36fd7/pz/9qdVAeElJSRx99NFx/PHHx9/93d/t8fsf/vCHKC8vj2XLluXwRQAAAAAAAAAAAJAdoXAAAAAAADJm/j/27jvKyvLcG/C9hzYwIKAUpRdBxBMkJpoIFrAmKqKHgOUzEYOx4IkmS5RjrBiNoEaNn4rHmuRoimDBEqOigkYUY43IqEHKCKh0ZGBgKPv7w+X+3AMbZmCGeWd7XWux8j7Pfsq9IX/dy99+b7ghJk2alDV3zjnnRElJScyePTvefvvtWLZsWTzyyCPRqVOnzJo1a9bEsGHDYuXKlTVW2/Dhw+Pjjz/OjAsLC+OWW26JJUuWxIwZM2LmzJmxZMmSuOmmm7LC4f/+97/jpz/9aZXuatCgQZx44onx4IMPxoIFC+Lzzz+Pf/3rX/HGG2/EwoULo7i4OM4444ysPUuWLIkf/OAHsWbNmh37ogAAAAAAAAAAAFCBUDgAAAAAABERsXTp0rj22muz5q677roYP358tGvXLjNXUFAQJ554YkybNi26dOmSmZ8/f37cdNNNNVLbs88+G08//XRm3KBBg3jmmWfiggsuiCZNmmTmi4qK4pe//GX8/e9/jwYNGmTmn3jiiXjxxRe3eU+zZs3i8ssvj08++SQeeeSROPXUU7O++1d69eoV9913X/zxj3+MVCqVmS8pKYlx48Zt79cEAAAAAAAAAACALRIKBwAAAAAgIiKuv/76WLVqVWZ8yCGHxOjRo3Oub9++fdxzzz1ZczfffHMsXbq02mu7/PLLs8b//d//HYccckjO9YceeuhmtV922WVbveOEE06I2bNnx9VXXx1t27atVF0//vGP4xe/+EXW3L333lupvQAAAAAAAAAAAFBZQuEAAAAAAMSmTZvi/vvvz5q76qqrst6CvSWHH354HHzwwZnxqlWr4qGHHqrW2t577714/fXXM+OioqK46KKLtrnv4osvjqKiosx42rRpUVxcnHP9QQcdFK1atapyfaNHj876e1qwYEHMmDGjyucAAAAAAAAAAABALkLhAAAAAADEtGnTYvHixZlxt27dYsCAAZXaO2LEiKzxY489Vo2VRUyaNClrPGzYsGjWrNk29zVr1iyGDh2aNVfdtUVEtG3bNnr27Jk1V1JSUu33AAAAAAAAAAAA8M0lFA4AAAAAQDz11FNZ4yOPPHKbbwn/+tqvmzJlSqxevbrGajvqqKMqvbdibU8++WS11FRRy5Yts8YrV66skXsAAAAAAAAAAAD4ZhIKBwAAAAAg3nnnnaxxv379Kr23Xbt20aVLl8y4vLw8Zs6cWS11pdPp+Ne//rXdtfXv3z9r/O6770Y6na6W2r5uwYIFWePddtut2u8AAAAAAAAAAADgm0soHAAAAACAKC4uzhr37t27Svsrrq943vaaN29erFmzJjMuKiqKTp06VXp/586do0mTJpnx6tWr45NPPqmW2r4yZ86cmD9/ftZcjx49qvUOAAAAAAAAAAAAvtmEwgEAAAAAvuHKysqipKQka65jx45VOqPi+g8//HCH69rSOVWta0t7qqu2r/z+97/Pevv43nvvHV27dq3WOwAAAAAAAAAAAPhmEwoHAAAAAPiGW7JkSVaouUGDBtGmTZsqndG+ffus8aJFi6qltorndOjQocpn1FRtERGffvpp3HLLLVlzw4cPr7bzAQAAAAAAAAAAICKifm0XAAAAAABA7SotLc0aN2nSJFKpVJXOKCoq2uqZ26viORXvqYyaqi2dTseZZ54ZX3zxRWauffv2cd5551XL+V9ZtGhRLF68uEp7Zs2aVa01AAAAAAAAAAAAULuEwgEAAAAAvuEqhqQLCwurfEbjxo23eub2SnJtY8eOjb/97W9Zc3fcccd2Bde35o477ogxY8ZU65kAAAAAAAAAAADULQW1XQAAAAAAALVr7dq1WeOGDRtW+YxGjRpljcvKynaopq8ktbZJkybFZZddljV3zjnnxPHHH7/DZwMAAAAAAAAAAEBFQuEAAAAAAN9wFd++XV5eXuUz1q1bt9Uzt1cSa3vttdfi1FNPjU2bNmXmDj744Ljlllt26FwAAAAAAAAAAADIpX5tFwAAAAAAQO1q2rRp1rji27kro+Lbtyueub2SVtv7778fxx57bKxZsyYzt++++8YTTzyx2RvJq8vIkSNj6NChVdoza9asOOGEE2qkHgAAAAAAAAAAAHY+oXAAAAAAgG+4iiHpNWvWRDqdjlQqVekzVq9evdUzq6u2ivdURnXVNmfOnDjqqKNi2bJlmbkePXrEM888E82bN9+uMyujTZs20aZNmxo7HwAAAAAAAAAAgOQrqO0CAAAAAACoXa1atcoKgK9fvz4WLVpUpTMWLFiQNa6uEHPFc+bPn1/lM6qjtoULF8YRRxwRCxcuzMx17NgxJk+eHG3btq3yeQAAAAAAAAAAAFAVQuEAAAAAAN9wjRs3jk6dOmXNlZSUVOmMiut79eq1w3VFROy1115Z408++aTKZ1TcU9XalixZEkcccUTMnj07M9emTZuYPHnyZn9vAAAAAAAAAAAAUBOEwgEAAAAA2CwoPXPmzCrtLy4u3up526tz587RuHHjzHj16tUxb968Su+fN29erFmzJjMuKiqKjh07Vnr/ypUr4+ijj876fi1atIhnn302evbsWelzAAAAAAAAAAAAYEcIhQMAAAAAEH379s0aT5s2rdJ7P/3005g7d25m3KBBg+jdu3e11JVKpaJPnz7bXdsrr7ySNe7Tp0+kUqlK7V29enUce+yx8dZbb2XmmjZtGk8//XTsu+++la4BAAAAAAAAAAAAdpRQOAAAAAAAcdxxx2WNJ0+eHOl0ulJ7n3322azxwIEDo2nTpjVW23PPPVfpvRXXDho0qFL71q1bFyeccEJWqLywsDAmTZoU3//+9yt9PwAAAAAAAAAAAFQHoXAAAAAAAKJfv37RqlWrzHj27NkxZcqUSu299957s8aDBw+uztLi+OOPzxpPmDAhSktLt7lv1apVMWHChCrXtmHDhhg2bFhMnjw5M9egQYOYMGFCHHbYYZWsGgAAAAAAAAAAAKqPUDgAAAAAAFFQUBDDhw/PmhszZsw23xb+/PPPx8svv5wZN2vWLIYNG1attfXp0yf233//zLi0tDSuv/76be67/vrrY/Xq1Znx97///ejdu/dW92zatCmGDx8ejz/+eGauoKAgHnjggc3eWA4AAAAAAAAAAAA7i1A4AAAAAAARETF69Oho2rRpZjx16tQYN25czvULFiyIM888M2vuggsuyHrj+JakUqmsP5V5I/nVV1+dNR47dmy89NJLOddvqfZrrrlmm/ecd9558eCDD2bVes8991R70B0AAAAAAAAAAACqon5tFwAAAAAAQDK0atUqfvWrX8WvfvWrzNwll1wSJSUlcdlll0W7du0i4su3aT/++ONxwQUXRElJSWZtu3bt4sILL6yR2n7wgx/EUUcdFc8++2xERKxfvz6OPvroGDt2bPzsZz+LJk2aRETE6tWr4+67745LLrkk1q9fn9l/zDHHxOGHH77VO8aMGRN33nln1tyQIUOiY8eOMXny5CrV261bt+jWrVuV9gAAAAAAAAAAAEAuQuEAAAAAAGSMHj06pk2bFk8++WRmbvz48XHXXXdF586do3nz5jFnzpxYsWJF1r7GjRvHQw89FC1atKix2v74xz/GgQceGHPmzImIiLVr18YvfvGLuOSSS6Jbt26RTqdj9uzZsXbt2qx93bt3j9///vfbPP/FF1/cbG7ixIkxceLEKtd65ZVXxlVXXVXlfQAAAAAAAAAAALAlBbVdAAAAAAAAyVFQUBATJkyIk08+OWt+48aNMXv27Hj77bc3C4Tvtttu8be//S369+9fo7W1bds2Xnzxxdh3332z5svKyuL999+PmTNnbhYI79u3b7z44ovRunXrGq0NAAAAAAAAAAAAapJQOAAAAAAAWQoLC+PPf/5zTJw4Mfr27ZtzXVFRUYwcOTJmzpwZAwYM2Cm1de7cOV5//fUYN25ctGvXLue6du3axfXXXx/Tp0+Pjh077pTaAAAAAAAAAAAAoKbUr+0CAAAAAABIpiFDhsSQIUNi1qxZMX369FiwYEGUl5dHixYtYu+9947+/ftHYWFhlc9Np9M7VFfDhg3j4osvjlGjRsWbb74Z7777bixatCgiItq0aRN9+/aN/fbbLwoKqva7qFOmTNmhugAAAAAAAAAAAKCmCIUDAAAAALBVe+65Z+y55561XcZmCgoKYv/994/999+/tksBAAAAAAAAAACAGlW116QAAAAAAAAAAAAAAAAAAACwUwmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQILVr+0C2PnWrVsXb7/9dhQXF8fy5cujrKwsdtlll2jTpk3st99+seeee0YqldrhezZs2BDTp0+PGTNmxNKlS6NevXqxxx57xHe+853YZ599quGb/H8LFiyIV199NebNm5f5Pj179oyDDjoomjZtWq13AQAAAAAAAAAAAAAAAADAziQU/g3y5ptvxs033xwTJ06MdevW5VzXvn37GDFiRFxwwQWx6667Vvme0tLSGDt2bIwfPz6WLVu2xTV77bVXjB49OoYPH75DAfSpU6fGVVddFVOmTNni5w0bNoyTTjoprr766ujSpct23wMAAAAAAAAAAAAAAAAAALWloLYLoOZt2rQp/vu//zsOOOCAePDBB7caCI/48q3bV199dfTu3Tv+/ve/V+mu9957L/r06RPXXnttzkB4RMSHH34YP/3pT+OHP/xhrFy5skp3RESk0+m4+OKLY8CAATkD4RER5eXl8b//+7/xH//xH/Hwww9X+R4AAAAAAAAAAAAAAAAAAKhtQuHfAGeffXaMGzcuNm3alDXfpEmT+Na3vhUHHHBAdO/efbM3dn/++ecxePDgePrppyt1z4cffhiHHXZYzJkzJ2u+adOm0adPn+jRo0c0aNAg67NnnnkmfvjDH8batWur9J3OP//8uOGGG7LmUqlUdOzYMfbbb79o1apV1merV6+Ok046KR599NEq3QMAAAAAAAAAAAAAAAAAALVNKDzPTZw4Me65556sud69e8dTTz0VK1eujH/9618xffr0mDVrVnz++ecxZsyYaNiwYWZteXl5nH766bF8+fKt3rNhw4YYOnRoLFmyJDO36667xh/+8IdYtmxZvPvuu/HRRx/FZ599FpdeemkUFPz//+u9+uqrcfHFF1f6Oz300ENx2223Zc0NGTIkPvzwwygpKYk333wzFi9eHJMnT44+ffpk1mzcuDFOP/30mDt3bqXvAgAAAAAAAAAAAAAAAACA2iYUnufGjBmTNf7ud78br7/+ehxzzDFRv379rM9at24dV1xxRTz99NNZny1evDjuvPPOrd5z3333xXvvvZcZt2zZMl5++eX4yU9+kvV28F133TWuueaa+N///d+s/ePHj49///vf2/w+5eXlMXr06Ky5c845JyZMmBA9evTImj/88MPjpZdeiu9+97uZuVWrVsWVV165zXsAAAAAAAAAAAAAAAAAACAphMLz2OzZs2PGjBlZc3fccUcUFRVtdd9hhx0WI0aMyJp74okncq4vLy+Pa665JmvuxhtvjN69e+fcc+qpp8Zpp52WGW/YsCGuuuqqrdYVEXHvvfdmvem7R48ecfPNN0cqldri+ubNm8cf/vCHrLefP/jgg/HBBx9s8y4AAAAAAAAAAAAAAAAAAEgCofA89uGHH2aNO3ToEPvvv3+l9g4ZMiRrPGvWrJxrn3nmmfjkk08y4y5dusQZZ5yxzTuuuuqqrDD3hAkTYuXKlVvdc88992SNL7nkkigsLNzqnt69e8dJJ52UGW/cuDHuv//+bdYHAAAAAAAAAAAAAAAAAABJIBSex5YtW5Y17tixY6X3durUKWu8YsWKnGsnTZqUNT7jjDNyvrn767p37x6HHnpoZrx+/fr429/+lnP9/Pnz46233sqMmzZtGsOGDdvmPRGx2ZvPK9YMAAAAAAAAAAAAAAAAAABJJRSex5o3b541Lisrq/TeimtbtWqVc+1TTz2VNT7qqKMqfc+RRx6ZNX7yyScrfU///v2jqKioUvf0798/mjRpkhl/+OGH8e9//7vSdQIAAAAAAAAAAAAAAAAAQG0RCs9jffv2zRoXFxfH6tWrK7X39ddfzxofcMABW1z3+eefx2effZYZN2rUKPbbb79K19i/f/+s8TvvvJNzbcXP+vXrV+l76tevv9l32NpdAAAAAAAAAAAAAAAAAACQFELheaxDhw5Zwel169bFrbfeus1969ati1tuuSVrbsSIEVtcW1xcnDXec889o2HDhpWusXfv3lnjWbNmxYYNGyp1V8W9Vb2r4nkAAAAAAAAAAAAAAAAAAJBEQuF5bty4cVFQ8P//ma+44or4wx/+kHP9ihUr4kc/+lFWYHrQoEExaNCgLa7/8MMPs8YdO3asUn2tW7eOwsLCzLi8vDzmzJlTI3dVXF/xPAAAAAAAAAAAAAAAAAAASKL6tV0ANeuggw6K2267Lc4777xIp9OxYcOGGD58eNx+++3xn//5n7HXXntF48aNY8mSJTF9+vT405/+FMuWLcvsP/LII+PPf/5zzvMXLVqUNe7QoUOVa2zXrl3Mnj0768wePXpstm7x4sU7dFf79u2zxhVr316LFi3arLZtmTVrVrXcDQAAAAAAAAAAAAAAAABA/hMK/wY499xzY6+99orzzz8/3n///YiI+Oc//xn//Oc/c+7p1q1bXHzxxfGzn/0s603jFZWWlmaNi4qKqlxfxT0Vz4yIKCsri40bN+7QXZW5Z3vccccdMWbMmGo5CwAAAAAAAAAAAAAAAAAAKsqd9iWvHHbYYfHPf/4zRo0aFfXq1dvq2k6dOsWoUaPi1FNP3WogPGLzYHVhYWGVa2vcuPFWz8w1V9W7KnMPAAAAAAAAAAAAAAAAAAAkjVD4N8Sdd94Z3bt3jxtvvHGzN25XVFJSEiNHjowuXbrEfffdt9W1a9euzRo3bNiwyrU1atQoa1xWVrbNe7bnrsrcAwAAAAAAAAAAAAAAAAAASVO/tgugZq1fvz5OOeWUePjhhzNzu+66a/zXf/1XHHfccdGjR48oKiqKJUuWxBtvvBH3339/PPbYY5FOp2PZsmUxYsSIKC4ujhtuuGGL51d8W3d5eXmVa1y3bt1Wz8w1V15eXqW3hVfmnu0xcuTIGDp0aJX2zJo1K0444YRquR8AAAAAAAAAAAAAAAAAgPwmFJ7nzj333KxA+AEHHBCTJk2K3XffPWvdHnvsEYMGDYpBgwbF448/HieddFLm7dw33nhj9O7dO84444zNzm/atGnWeEtv9N6Wim/srnhmrrm1a9dWKdhdmXu2R5s2baJNmzbVchYAAAAAAAAAAAAAAAAAAFRUUNsFUHOmTJkS9957b2bcpk2bePLJJzcLhFd0/PHHx+233541d9FFF20Wqo7YPFi9evXqKtdZcc+WwtqNGzeOevXq7dBdlbkHAAAAAAAAAAAAAAAAAACSRig8j916661Z41/84hfRunXrSu0dPnx49OzZMzNeunRpPPLII5utq/iG7Pnz51e5zoULF271zK9UrL2qdy1YsKBS9wAAAAAAAAAAAAAAAAAAQJIIheepdDodL7zwQtbcoEGDKr2/oKAgjj322Ky5l156abN1e+21V9a4pKSkClVGLFq0KNauXZsZN2zYMLp167bFtTt6V8X1vXr1qtJ+AAAAAAAAAAAAAAAAAACoDULheWr58uWxcuXKrLmuXbtW6YyK6yu+aTti82D1xx9/HOXl5ZW+o7i4OGvcvXv3qF+//hbXVrxr5syZlb5nS3cJhQMAAAAAAAAAAAAAAAAAUBcIheepdevWbTaXK2ydS4MGDbLGGzdu3GzN7rvvHrvvvnvWvW+++Wal73jllVeyxn379s25tuJn06ZNq/Q9GzZsiNdff73SdwEAAAAAAAAAAAAAAAAAQFIIheep3XbbbbO5hQsXVumMim8Gb9269RbXHXvssVnj5557rtJ3VFw7aNCgnGsr3jNt2rRYvXp1pe555ZVXYs2aNZlxz549o2fPnpWuEwAAAAAAAAAAAAAAAAAAaotQeJ5q2LBh7LHHHllzL7zwQpXOeP7557PG3bt33+K6448/Pmt8//33Rzqd3ub5H3/8cUydOjUzbtCgQRxzzDE513fs2DG+/e1vZ8alpaXx0EMPbfOeiIh77703azx48OBK7QMAAAAAAAAAAAAAAAAAgNomFJ7HDj/88KzxLbfcEhs2bKjU3qlTp8arr7661fO+cvTRR0eHDh0y47lz58b999+/zTuuuuqqrPD4kCFDonnz5lvdM2LEiKzx2LFjY+3atVvdU1xcHH/9618z44KCghg+fPg26wMAAAAAAAAAAAAAAAAAgCQQCs9jp512WtZ4xowZMXLkyNi0adNW982aNStOPfXUrLkePXrEgQceuMX1jRo1iksvvTRrbtSoUTFz5sycd/zpT3+KBx54IDOuV69ejBkzZqt1RUT87Gc/i06dOmXGH330Ufzyl7/M+WbyL774In7yk59EeXl5Zu7UU0+N3r17b/MuAAAAAAAAAAAAAAAAAABIAqHwPHb00UfHwIEDs+buvvvuOPTQQ+P555/f7K3hS5cujd/+9rfx3e9+NxYuXJj12W9+85uoV69ezrtGjBgR++yzT2a8fPnyOPjgg+OPf/xj1j3Lli2Lyy+/PH784x9n7T/77LOjZ8+e2/xODRs2jLFjx2bN3XnnnTFs2LD497//nTX/wgsvxMEHHxxvvPFGZq5p06Zx9dVXb/MeAAAAAAAAAAAAAAAAAABIivq1XQA1609/+lP069cv5syZk5n7xz/+EUcccUQ0bdo0unbtGo0bN46lS5fG7Nmzt/jG7QsvvDB+9KMfbfWeBg0axIQJE+Kggw6KZcuWRcSXAfDTTz89zjvvvOjevXuUlZXFnDlzYv369Vl7DzjggLjxxhsr/Z1OOeWUePnll2P8+PGZuYkTJ8bDDz8cHTt2jNatW8e8efNiyZIlWfsKCgri/vvvj65du1b6LgAAAAAAAAAAAAAAAAAAqG3eFJ7ndt9995g6dWoMGDBgs89KS0vjvffei9dffz0+/vjjzQLhDRo0iLFjx8YNN9xQqbv23nvveOGFF6Jz586b3fPuu+/GRx99tFkg/IgjjohnnnkmGjduXKXvddttt8Uvf/nLrLl0Oh0lJSXx5ptvbhYIb9KkSfz5z3/eZrgdAAAAAAAAAAAAAAAAAACSRij8G6Bjx47x/PPPx0MPPRQDBgyIgoKt/7M3b948zj333Hjvvfdi9OjRkUqlKn3XvvvuG++9915ccskl0bJly5zrevToEXfffXc8++yz0aJFi0qf/5WCgoK46aab4oUXXoiDDz4457qGDRvG//k//ydmzJgRw4YNq/I9AAAAAAAAAAAAAAAAAABQ2+rXdgHsHAUFBTF06NAYOnRorFq1Kt54442YPXt2rFixItauXRu77LJL7LbbbtGnT5/o3bv3NoPjW9OsWbP4zW9+E2PGjInp06fHjBkzYunSpVGvXr3YY489Yr/99otvfetb1fK9Bg4cGAMHDoz58+fHtGnToqSkJNauXRvNmjWLHj16xEEHHRS77LJLtdwFAAAAAAAAAAAAAAAAAAC1QSj8G6hZs2aZMHVNatCgQRx00EFx0EEH1eg9EREdOnTwJnAAAAAAAAAAAAAAAAAAAPLS9r8OGgAAAAAAAAAAAAAAAAAAgBonFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAlWv7YLAAAAAAAAAAAAAIAkWbt2bUybNi0++OCDWL58eTRs2DA6dOgQ3/ve96Jbt27VetfHH38cr7/+esyfPz/Ky8ujZcuW0atXr+jXr18UFhZW610AAAAA1F1C4QAAAAAAAAAAAADUWaecckr85S9/yZrr3LlzzJ07t8pnLV68OMaMGRO///3vY/Xq1Vtc853vfCcuv/zyGDx48PaUm/HYY4/Fr3/963jrrbe2+HnTpk1j+PDhceWVV0arVq126C4AAAAA6r6C2i4AAAAAAAAAAAAAALbHE088sVkgfHtNmTIlevfuHbfffnvOQHhExJtvvhknnHBCnH766VFeXl7le9atWxennXZanHjiiTkD4RERpaWlcdttt0Xv3r3jpZdeqvI9AAAAAOQXoXAAAAAAAAAAAAAA6pyVK1fGueeeWy1n/eMf/4hjjjkmlixZkjXfokWL+Pa3vx1dunSJevXqZX32xz/+MU455ZRIp9OVvmfTpk1x0kknxYMPPpg1X69evejatWv07ds3mjdvnvXZ4sWL44c//GG8+uqrVfxWAAAAAOQToXAAAAAAAAAAAAAA6pyLLrooFixYEBERRUVF233O8uXL46STToqysrLMXOfOneOxxx6LZcuWxVtvvRVz5syJuXPnxtlnn52195FHHombb7650nfdcMMNMWnSpKy5c845J0pKSmL27Nnx9ttvx7Jly+KRRx6JTp06ZdasWbMmhg0bFitXrtzObwkAAABAXScUDgAAAAAAAAAAAECdMmXKlLjnnnsiIqKgoCCuvPLK7T7rhhtuiIULF2bGXbt2jWnTpsXgwYMjlUpl5jt06BB33nlnXHvttVn7r7766li+fPk271m6dOlme6+77roYP358tGvXLjNXUFAQJ554YkybNi26dOmSmZ8/f37cdNNNVf16AAAAAOQJoXAAAAAAAAAAAAAA6oyysrI488wzI51OR0TEz3/+89h///2366zFixfH//2//zdr7u67784KaVd0ySWXxCGHHJIZr1y5Mm688cZt3nX99dfHqlWrMuNDDjkkRo8enXN9+/btM8H3r9x8882xdOnSbd4FAAAAQP4RCgcAAAAAAAAAAACgzrj88svj448/joiITp06xTXXXLPdZ/3lL3+J0tLSzPiQQw6Jww8/fKt7UqnUZm8mv++++zIh9S3ZtGlT3H///VlzV111VdabyLfk8MMPj4MPPjgzXrVqVTz00ENb3QMAAABAfhIKBwAAAAAAAAAAAKBO+Oc//xm33HJLZnz77bdH06ZNt/u8SZMmZY1HjBhRqX0DBw6Mrl27ZsafffZZvPbaaznXT5s2LRYvXpwZd+vWLQYMGFCpuyrW9Nhjj1VqHwAAAAD5RSgcAAAAAAAAAAAAgMRbv359jBgxIjZu3BgREUOHDo3jjjtuu88rLS2Nl156KWvuqKOOqtTeVCoVRxxxRNbck08+mXP9U089lTU+8sgjt/mW8K+v/bopU6bE6tWrK7UXAAAAgPwhFA4AAAAAAAAAAABA4l133XXx3nvvRUREixYt4tZbb92h895///1Yv359Zty1a9fYfffdK72/f//+WeN33nkn59qKn/Xr16/S97Rr1y66dOmSGZeXl8fMmTMrvR8AAACA/CAUDgAAAAAAAAAAAECizZw5M6699trMeNy4cVUKcG9JcXFx1rh3795V2l9xfcXzausuAAAAAPJT/douoKbMnz8/br/99vjHP/4RS5YsiZYtW8Z3vvOd+OlPfxrf/va3a7s8AAAAAGAn0SsEAAAAAMitLvRQN23aFCNGjIjy8vKIiDj44IPjZz/72Q6f++GHH2aNO3bsWKX9FdfPmzcv1q5dG4WFhVnzZWVlUVJSUq13VawdAAAAgPxXJ0Lh06dPj9tvvz0zvuKKK2LPPffMuX7ixIlx+umnx9q1ayMiIp1ORyqViunTp8edd94Zo0ePjmuuuabG6wYAAAAAqpdeIQAAAABAbvnaQ7311lvjtddei4iIhg0bxl133RWpVGqHz120aFHWuEOHDlXa37Zt26hfv35s2LAhIr4Mry9dujTat2+ftW7JkiWRTqcz4wYNGkSbNm2qdFfFMyvWDgAAAED+qxOh8LvuuiseeOCBSKVS0a1bt602KN9888047bTTMr8GmUqlshp/GzdujOuuuy4aNmwYV1xxRY3XDgAAAABUH71CAAAAAIDc8rGHOmfOnLjssssy40suuSR69epVLWeXlpZmjYuKiqq0P5VKRePGjWPVqlU5z9zSXJMmTaocaq9Y25bu2V6LFi2KxYsXV2nPrFmzqu1+AAAAACqnToTCn3nmmczzqaeeutW1v/jFL6K8vDzTLPv6LytGfNmAS6fTcc0118SQIUNin332qf6CAQAAAIAaoVcIAAAAAJBbPvZQzzrrrFi9enVERPTq1St+9atfVdvZFYPVhYWFVT5je0Lh23vP1s7cEXfccUeMGTOm2s4DAAAAoGYU1HYB2zJ//vxYuHBhZnzMMcfkXPv666/HK6+8kmlQdu3aNSZPnhxlZWXxySefxM9//vNIp9ORSqVi48aNccMNN9R4/QAAAABA9dArBAAAAADILR97qPfee29Mnjw5Ir4Mqd91113RsGHDajt/7dq1WePtObtRo0ZZ47Kyslq7BwAAAID8lvhQ+AcffJB5LigoiL59++Zc+6c//Skivvy1yoKCgnj88cfjsMMOi0aNGkX79u3jd7/7XQwbNizS6XSk0+l49NFHY/369TX9FQAAAACAaqBXCAAAAACQW771UD/99NMYNWpUZnzmmWfGwQcfXK13VHxjd3l5eZXPWLdu3VbP3Jn3AAAAAJDfEh8Knzt3bkR8+QuPnTp12uyXDr/umWeeyaw96qijonfv3putueSSSzLPpaWl8d5771VvwQAAAABAjdArBAAAAADILd96qOedd16sWLEiIiJ23333uP7666v9jqZNm2aNK77RuzIqvrG74pk7857tNXLkyJgxY0aV/jz22GPVdj8AAAAAlVO/tgvYli+++CLz3LJly5zrPv/88/jwww8jlUpFRMR//ud/bnHdvvvuGy1atMg0Ct9///3Yb7/9qq9gAAAAAKBG6BUCAAAAAOSWTz3UCRMmxKOPPpoZ/+53v4sWLVpU+z0Vg9WrV6+u0v50Or1dofA1a9ZEOp3O/BtURsXaqjMU3qZNm2jTpk21nQcAAABAzUj8m8K/3izb2q9WvvrqqxHxZYMtIuLwww/PubZLly6Z56VLl+5ghQAAAADAzqBXCAAAAACQWz71UC+66KLM87HHHhvDhg2rkXsqBqHnz59fpf2ff/55bNiwITMuKCiIVq1abbauVatWWQHw9evXx6JFi6p014IFC7LGQtwAAAAA3zyJD4U3btw48/z1X7GsaOrUqZnndu3aZTUiKyosLMw8r1mzZscKBAAAAAB2Cr1CAAAAAIDc8qmH+tXbySMinnrqqUilUtv8M3DgwKwz5s2bt9mad955J2vNXnvtlTUuKSmpUp0V13fu3Dnr7+wrjRs3jk6dOlXrXb169arSfgAAAADqvsSHwlu2bBkRX/4i5dy5czO/TFnRs88+GxERqVQqDjnkkK2euWrVqszz1n4NEwAAAABIDr1CAAAAAIDc9FCrrmKweubMmVXaX1xcvNXzausuAAAAAPJT4kPhvXv3zjyvWbMmXnnllc3WzJgxI4qLiyOVSkVExIABA7Z65qJFizLPXzVBAQAAAIBk0ysEAAAAAMhND7Xq9tlnn2jQoEFmPHfu3Pj0008rvb/i33Hfvn1zrq342bRp0yp9z6effhpz587NjBs0aJD17w0AAADAN0P92i5gW/bdd98oKiqKNWvWRETEmDFj4rnnnsta8+tf/zoivvx1y1QqFUcddVTO8z777LNYvHhxZty1a9caqBoAAAAAqG56hQAAAAAAueVTD3XSpEmxfv36Ku159913Y9SoUZlx27Zt44EHHshas+eee2aNmzVrFoccckg8//zzmbnnnnsufvKTn2zzvnQ6HZMnT86aGzRoUM71xx13XIwbNy4znjx5cubfYVu+erv7VwYOHBhNmzbd5j4AAAAA8kviQ+GFhYVx4oknxgMPPBCpVCpeeOGFOPLII+Oss86KBg0axIMPPhgPP/xwpil20EEHRefOnXOe99prr2WNe/XqVaP1AwAAAADVQ68QAAAAACC3fOqhHnrooVXeU79+9n8SW1hYGEccccQ29x1//PFZofB77723UqHwF198MebMmZMZt23bNr73ve/lXN+vX79o1apVLFmyJCIiZs+eHVOmTImBAwdu86577703azx48OBt7gEAAAAg/xTUdgGVceWVV0ajRo0i4stfVnzhhRfi5JNPjiFDhsQjjzySmY+IuOyyy7Z61mOPPZZ57tixY+yxxx41UzQAAAAAUO30CgEAAAAActNDrbqTTz45ioqKMuOXXnopXnjhha3uSafTMWbMmKy5M844IwoKcv9nuQUFBTF8+PCsuTFjxmT+PXJ5/vnn4+WXX86MmzVrFsOGDdvqHgAAAADyU50IhXfv3j3uuuuuiIjML1Sm0+lMI+yrubPOOiuOPPLInOeUlZXFpEmTIpVKRSqV2q5fkgQAAAAAao9eIQAAAABAbnqoVdemTZv4r//6r6y5M888MxYuXJhzz3XXXRcvvfRSZty8efO46KKLtnnX6NGjo2nTppnx1KlTY9y4cTnXL1iwIM4888ysuQsuuCBatWq1zbsAAAAAyD91IhQeEfHjH/84/v73v0evXr2yfhUxnU5Hs2bN4tprr43x48dv9Yz7778/Vq5cmdl/3HHH1WjNAAAAAED10ysEAAAAAMhND7XqLr744th9990z4zlz5kS/fv3i8ccfz/o7nD9/fpxzzjlx6aWXZu2/9NJLY9ddd93mPa1atYpf/epXWXOXXHJJjBw5MiuEvmnTpnjssceiX79+MXfu3Mx8u3bt4sILL6zq1wMAAAAgT9Sv7QKq4sgjj4z3338/iouL46OPPoqysrJo165dfO9734tGjRptc/+GDRviggsuyIx/+MMf1mS5AAAAAEAN0SsEAAAAAMhND7Vqdt111/jrX/8aRx99dKxduzYiIubNmxeDBw+OFi1aRNeuXWPFihVRUlISGzduzNo7ePDgGDVqVKXvGj16dEybNi2efPLJzNz48ePjrrvuis6dO0fz5s1jzpw5sWLFiqx9jRs3joceeihatGix3d8TAAAAgLqtToXCv7L33nvH3nvvXeV9559/fg1UAwAAAADUFr1CAAAAAIDc9FAr75BDDomnnnoqhg4dGsuWLcvMr1ixIt5+++0t7jn11FPjvvvui1QqVel7CgoKYsKECXHGGWfEX/7yl8z8xo0bY/bs2Vvcs9tuu8XEiROjf//+lb4HAAAAgPxTUNsFAAAAAAAAAAAAAEBtO+yww2LmzJlx7rnnRpMmTXKu+/a3vx0PP/xwPPjgg5V683pFhYWF8ec//zkmTpwYffv2zbmuqKgoRo4cGTNnzowBAwZU+R4AAAAA8kudfFM4AAAAAAAAAAAAAHxlwIABkU6nd/ictm3bxh133BG//e1vY9q0aVFcXBwrVqyIhg0bRvv27eN73/te7LnnntVQccSQIUNiyJAhMWvWrJg+fXosWLAgysvLo0WLFrH33ntH//79o7CwsFruAgAAAKDuEwoHAAAAAAAAAAAAgK9p3LhxHH744XH44YfX+F177rlntQXNAQAAAMhfdTYU/sUXX8QzzzwTL7/8chQXF8eyZcti5cqVkU6n44EHHogDDzywtksEAAAAAHYCvUIAAAAAgNz0UAEAAAAgP9S5UPjy5cvj6quvjvvuuy9KS0uzPkun05FKpaKsrGyLe08++eSYMGFCRER06tQp5syZU+P1AgAAAAA1Q68QAAAAACA3PVQAAAAAyC8FtV1AVUybNi369u0bt956a6xatSrS6XSV9l900UWRTqcjnU5HSUlJPP/88zVUKQAAAABQk/QKAQAAAABy00MFAAAAgPxTZ0Lhb7zxRhx11FExf/78rPlUKhWtWrWqVMPyO9/5Tuy3336Z8cSJE6u9TgAAAACgZukVAgAAAADkpocKAAAAAPmpToTCS0tL4/jjj481a9ZEREQ6nY7vf//7MWnSpPjiiy/i888/j4gvG5bbMmTIkMwZzz77bM0VDQAAAABUO71CAAAAAIDc9FABAAAAIH/ViVD4DTfcEJ999lmmCfnzn/88/vGPf8SgQYOiSZMmVTrriCOOyDzPnTs3Pvvss2qtFQAAAACoOXqFAAAAAAC56aECAAAAQP6qE6Hw//mf/8k0KA877LD43e9+FwUF21d6nz59ol69epnxzJkzq6VGAAAAAKDm6RUCAAAAAOSmhwoAAAAA+SvxofC33norFi1aFOl0OiIirr766h06r1GjRtGhQ4fMeM6cOTt0HgAAAACwc+gVAgAAAADkpocKAAAAAPkt8aHwr/+yZMuWLePAAw/c4TNbtGiReV65cuUOnwcAAAAA1Dy9QgAAAACA3PRQAQAAACC/JT4UvmjRooiISKVS0blz52o5s7CwMPO8bt26ajkTAAAAAKhZeoUAAAAAALnpoQIAAABAfkt8KHzjxo2Z53r16lXLmcuXL888f/1XLAEAAACA5NIrBAAAAADITQ8VAAAAAPJb4kPhbdq0iYiIdDodn3/++Q6fV15eHvPmzcuMW7VqtcNnAgAAAAA1T68QAAAAACA3PVQAAAAAyG+JD4W3b98+8zx//vxYtGjRDp33yiuvxLp16zLjffbZZ4fOAwAAAAB2Dr1CAAAAAIDc9FABAAAAIL8lPhTev3//aNSoUaRSqYiIePDBB3fovNtuuy3z3KZNm+jdu/cOnQcAAAAA7Bx6hQAAAAAAuemhAgAAAEB+S3wovHHjxjFw4MBIp9ORTqdj3LhxsXTp0u0664knnojHHnssUqlUpFKpOOGEE6q3WAAAAACgxugVAgAAAADkpocKAAAAAPkt8aHwiIhLL700IiJSqVQsXrw4jj/++FixYkWVznj66afjtNNOi4iIdDod9evXj9GjR1d3qQAAAABADdIrBAAAAADITQ8VAAAAAPJXnQiF9+/fP370ox9FOp2OiIjXXnst/uM//iPuvffeKC0tzblv48aNMW3atDjllFPi+OOPj1WrVkU6nY5UKhXnn39+dOnSZSd9AwAAAACgOugVAgAAAADkpocKAAAAAPmrfm0XUFm///3vY/bs2fHWW29FKpWKhQsXxllnnRUjR46Mnj17RkRkGpAXXHBBpNPpmDdvXqxZsybrs3Q6HQMGDIhx48bV5tcBAAAAALaTXiEAAAAAQG56qAAAAACQn+rEm8IjIpo0aRJPP/10DBgwIKvhuH79+nj//fcz69LpdMycOTNmzpwZq1evzvza5VfrjznmmHj00UejoKDOfHUAAAAA4Gv0CgEAAAAActNDBQAAAID8VKc6da1bt47nn38+rrvuumjZsmVmPpVKZf35+lzEl43L5s2bx3XXXRdPPPFE7LLLLrVSPwAAAABQPfQKAQAAAABy00MFAAAAgPxTp0LhEV82H0ePHh2ffPJJjB8/PgYNGhQtW7aMdDq92Z/CwsI44ogj4sYbb4y5c+fG6NGjM41LAAAAAKBu0ysEAAAAAMhNDxUAAAAA8kv92i5gezVu3DjOPvvsOPvssyMi4vPPP4+lS5fGihUrokmTJtGqVavYfffdo379OvsVAQAAAIBK0CsEAAAAAMhNDxUAAAAA8kPedPDatm0bbdu2re0yAAAAAIBaplcIAAAAAJCbHioAAAAA1E0FtV0AAAAAAAAAAAAAAAAAAAAAuQmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQILViVD4v/71r+jWrVvmz9SpU7frnClTpmTO6N69e3z00UfVXCkAAAAAUJP0CgEAAAAActNDBQAAAID8VSdC4ePHj4+5c+fG3Llzo0mTJnHooYdu1zkDBgyIRo0aZc76n//5n2quFAAAAACoSXqFAAAAAAC56aECAAAAQP6qE6HwSZMmRUREKpWK0047bYfO+slPfhIREel0Oh599NEdrg0AAAAA2Hn0CgEAAAAActNDBQAAAID8lfhQeHFxcXz22WeZ8eDBg3fovK/vnzdvXsyZM2eHzgMAAAAAdg69QgAAAACA3PRQAQAAACC/JT4UPnPmzMxz06ZNY++9996h8/bee+9o2rRpZjxjxowdOg8AAAAA2Dn0CgEAAAAActNDBQAAAID8lvhQ+IIFCyIiIpVKRceOHXf4vFQqFZ06dcqMS0pKdvhMAAAAAKDm6RUCAAAAAOSmhwoAAAAA+S3xofDS0tLM8y677FItZzZr1izzvGrVqmo5EwAAAACoWXqFAAAAAAC56aECAAAAQH5LfCj86w3F5cuXV8uZK1asyDw3bNiwWs4EAAAAAGqWXiEAAAAAQG56qAAAAACQ3xIfCm/VqlVERKTT6fjkk09i/fr1O3ReeXl5fPLJJ5lx69atd+g8AAAAAGDn0CsEAAAAAMhNDxUAAAAA8lviQ+Hdu3fPPJeVlcXUqVN36LypU6fGmjVrMuPOnTvv0HkAAAAAwM6hVwgAAAAAkJseKgAAAADkt8SHwr/73e9G8+bNI5VKRUTEddddt0PnjR07NvNcVFQUBx544A6dBwAAAADsHHqFAAAAAAC56aECAAAAQH5LfCi8oKAgjjnmmEin05FOp2PKlClx8803b9dZN910U7z44ouRSqUilUrF0UcfHQ0aNKjmigEAAACAmqBXCAAAAACQmx4qAAAAAOS3xIfCIyIuvfTSKCgoiFQqFel0Oi666KK44oorYuPGjZXav3Hjxrj88svj4osvzpyRSqXi8ssvr+HKAQAAAIDqpFcIAAAAAJCbHioAAAAA5K86EQrv3bt3nHXWWZnm4qZNm+Laa6+NXr16xc033xwffPDBFvd98MEHcdNNN0WvXr3iN7/5TWzatCkiIlKpVIwYMSL69OmzM78GAAAAALCD9AoBAAAAAHLTQwUAAACA/FW/tguorFtvvTXef//9ePnllzO/Pvnxxx/HqFGjYtSoUVFUVBStWrWKpk2bRmlpaSxZsiRWr14dERHpdDoiIrNvwIABcfvtt9fm1wEAAAAAtpNeIQAAAABAbnqoAAAAAJCf6sSbwiMi6tevH0888USccMIJmV+w/KrpmE6no7S0NObOnRszZsyIuXPnRmlpaeazr6/90Y9+FJMmTYr69etMHh4AAAAA+Bq9QgAAAACA3PRQAQAAACA/1ZlQeETELrvsEo888kiMHz8+OnbsmPWLlLn+RHz5y5WdO3eOe+65Jx566KFo1qxZbX4NAAAAAGAH6RUCAAAAAOSmhwoAAAAA+adO/nzj2WefHWeeeWY88sgj8eyzz8bLL78cs2fPjg0bNmTW1K9fP/bcc884+OCD4wc/+EEMHjw4CgrqVAYeAAAAANgGvUIAAAAAgNz0UAEAAAAgf9TJUHhERL169WLo0KExdOjQzNyqVati1apV0axZM79OCQAAAADfEHqFAAAAAAC56aECAAAAQH6os6HwLdGcBAAAAAAi9AoBAAAAALZGDxUAAAAA6p6C2i4AAAAAAAAAAAAAAAAAAACA3ITCAQAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMHq13YBO2r9+vWxcuXKKCsri3Q6XeX9nTp1qoGqAAAAAICdTa8QAAAAACA3PVQAAAAAqNvqXCh8+fLl8cADD8TTTz8db731VixevHi7z0qlUrFhw4ZqrA4AAAAA2Fn0CgEAAAAActNDBQAAAID8UqdC4bfccktcfvnlsWbNmoiI7fqlSgAAAACg7tMrBAAAAADITQ8VAAAAAPJPnQmFn3POOXH33XdnGpOpVCpSqZRGJQAAAAB8w+gVAgAAAADkpocKAAAAAPmpToTC//CHP8Rdd90VEZFpTKbT6WjZsmV861vfijZt2kRRUVEtVwkAAAAA1DS9QgAAAACA3PRQAQAAACB/1YlQ+BVXXBER/79Bue+++8bYsWPjyCOPjIKCglquDgAAAADYWfQKAQAAAABy00MFAAAAgPyV+FD422+/HZ988kmkUqmIiOjXr18899xz0bhx41quDAAAAADYmfQKAQAAAABy00MFAAAAgPyW+J99fOeddyIiIp1OR0TEbbfdpkEJAAAAAN9AeoUAAAAAALnpoQIAAABAfkt8KHzx4sWZ53bt2kXfvn1rrxgAAAAAoNboFQIAAAAA5KaHCgAAAAD5LfGh8FQqlfnf9u3b13I1AAAAAEBt0SsEAAAAAMhNDxUAAAAA8lviQ+GdOnXKPJeWltZiJQAAAABAbdIrBAAAAADITQ8VAAAAAPJb4kPh/fr1i4iIdDodc+fOjfLy8lquCAAAAACoDXqFAAAAAAC56aECAAAAQH5LfCi8Y8eOMXDgwIiIKCsri6effrqWKwIAAAAAaoNeIQAAAABAbnqoAAAAAJDfEh8Kj4gYO3Zs1KtXLyIiLr300li7dm0tVwQAAAAA1Aa9QgAAAACA3PRQAQAAACB/1YlQ+P777x+//e1vI51OR3FxcQwZMiRWrVpV22UBAAAAADuZXiEAAAAAQG56qAAAAACQv+pEKDwi4vzzz4/x48dHgwYN4u9//3v06dMn7rrrrli+fHltlwYAAAAA7ER6hQAAAAAAuemhAgAAAEB+ql/bBVTGYYcdlnlu3bp1LFiwIObNmxfnnntujBw5Mrp06RJt2rSJwsLCKp2bSqXi+eefr+5yAQAAAIAaolcIAAAAAJCbHioAAAAA5K86EQqfMmVKpFKpzPir53Q6Hel0OmbPnh1z5syp0pnpdDrrTAAAAAAg+fQKAQAAAABy00MFAAAAgPxVJ0LhuWgyAgAAAAAReoUAAAAAAFujhwoAAAAAdV+dCYWn0+naLgEAAAAASAC9QgAAAACA3PRQAQAAACA/1YlQ+KZNm2q7BAAAAAAgAfQKAQAAAABy00MFAAAAgPxVUNsFAAAAAAAAAAAAAAAAAAAAkJtQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkWP3aLmB7zZo1Kx599NF4+eWXo7i4OJYtWxYrV66MiIhnn302DjvssM32fPrpp7F+/fqIiGjcuHG0bt16p9YMAAAAAFQ/vUIAAAAAgNz0UAEAAAAgP9S5UPjs2bPjwgsvjCeeeCLS6XREROZ/IyJSqVTOvVdddVXcc889ERHRunXrWLBgQdSrV69mCwYAAAAAaoReIQAAAABAbnqoAAAAAJBfCmq7gKp4+OGHY7/99ovHH388Nm3alPXZ1pqTX7nwwgsj4sum5uLFi+PJJ5+skToBAAAAgJqlVwgAAAAAkJseKgAAAADknzoTCv/b3/4WJ598cnzxxReZuXQ6HW3bto39998/69crc+nZs2f0798/M37kkUdqpFYAAAAAoOboFQIAAAAA5KaHCgAAAAD5qU6EwhcvXhynnHJKbNy4MVKpVKTT6Rg6dGi8++67sXDhwpg+fXpEVO7XK4cMGRIRXzY4J0+eXKN1AwAAAADVS68QAAAAACA3PVQAAAAAyF91IhT+61//OlatWpUZX3/99fHXv/41vvWtb1X5rIEDB2aeP/vssygpKamWGgEAAACAmqdXCAAAAACQmx4qAAAAAOSvxIfCN23aFA888ECkUqlIpf4fe3ceZnVd9w38c2ZgGHZkVXZQRCCRRdRAEcTALbXHkFyzsDTq1jSDyLtbycoFH9EsLXcztRTNDfcUNSlUxAVBBBQQENkEYQCH5Tx/+HBuz8BhZmCGczi8Xtc1l+f7Pd/lc2b863PxPr9EfPvb345LLrlkh8/r2rVrFBUVpcYzZsyoijIBAAAAgGqmVwgAAAAAkJkeKgAAAADkt5wPhf/nP/+JlStXRjKZjIiI//7v/96p82rUqBGtWrVKjX1zJQAAAADsHvQKAQAAAAAy00MFAAAAgPyW86HwWbNmpV43b948DjzwwJ0+s1GjRqnXq1at2unzAAAAAIDqp1cIAAAAAJCZHioAAAAA5LecD4UvXbo0IiISiUS0bt26Ss6sUaNG6vXGjRur5EwAAAAAoHrpFQIAAAAAZKaHCgAAAAD5LedD4QUF/1vi5s2bq+TMFStWpF7vtddeVXImAAAAAFC99AoBAAAAADLTQwUAAACA/Faj/CXZ1axZs4iISCaTsXjx4p0+b+3atTFv3rxIJBJp5wMAAAAAuU2vMHvmzJkTr732WixYsCBKS0tjr732igMOOCD69u0bxcXFWasrmUzGm2++GW+99VYsWbIkIiJatGgRBx10UPTq1Sv1t60Ky5cvj1dffTXmzJkTJSUlUbdu3dh3332jX79+0aRJkyq7BwAAAAB2lB4qAAAAAOS3nA+Ft2/fPvV68eLFMW/evGjXrt0On/fiiy/Gxo0bIyIikUhEjx49drJCAAAAAGBX0Cvc9R555JG44oor4s0339zm+/Xq1YtzzjknLrvssmjatOkuq2vDhg1xww03xPXXXx8LFy7c5prWrVvHT3/607jggguiZs2aO3zX22+/Hf/zP/8TTzzxxDafrlRYWBjHH398XHHFFdG9e/cdvgcAAAAAdpYeKgAAAADkt4JsF1Ceww47LOrVq5f6psm77rprp84bN25c6nXbtm2jY8eOO3UeAAAAALBr6BXuOl988UWceeaZ8a1vfStjIDwiYs2aNfGHP/whunbtGi+//PIuqe3jjz+OQw89NH7+859nDIRHRCxYsCAuueSS+PrXv77dddtzww03xMEHHxyPPfbYNgPhERGbNm2Kxx57LHr37h033njjDt0DAAAAAFVBDxUAAAAA8lvOh8Jr1qwZxxxzTCSTyUgmk3HdddfF3Llzd+is2267LV544YVIJBKRSCTi1FNPrdpiAQAAAIBqo1e4a2zevDmGDRsW9957b9p8YWFhdOjQIXr06BENGzZMe2/p0qVx7LHHxr///e9qrW3JkiUxcODAmDp1atp87dq1o1u3btGlS5coLi5Oe2/KlCkxcODAWLZsWaXuuu666+KnP/1p6klIW+yzzz7Ru3fv2GeffdLmN27cGBdccEH8/ve/r9Q9AAAAAFBV9FABAAAAIL/lfCg8IuKyyy6LgoKCSCQSsXr16hgyZEilG5V//vOf4yc/+UkkEolIJpNRu3btuOSSS6qnYAAAAACgWugVVr+xY8fGo48+mjZ3/vnnx/z58+PDDz+MqVOnxooVK+Lhhx+Otm3bptasXbs2Tj311Fi1alW11XbOOefEnDlzUuPi4uK4/vrrY9myZTFt2rSYPn16LFu2LK677rq0cPisWbPi+9//foXvmTRpUowcOTJtbsCAATFlypRYtGhRvPHGG7Fo0aJ4/fXX48gjj0xb97Of/Sxee+21HfyEAAAAALBz9FABAAAAIH/tFqHwbt26xY9+9KNIJpORSCRi1qxZceCBB8avfvWr+OCDD7Zan0gkIiJi8eLFcd9990Xfvn1jxIgRUVpamjrj8ssvj2bNmu3qjwIAAAAA7AS9wuq1fPny+O1vf5s2d+WVV8bNN98cLVu2TM0VFBTEt771rZg0aVK0b98+Nb9gwYK47rrrqqW2Z599Np566qnUuGbNmvHMM8/EhRdeGHXq1EnN161bNy666KJ4+umno2bNmqn5xx9/PF588cUK3fXzn/88Nm3alBp/85vfjGeeeSZ69eqVtu7ggw+OZ599No4//vjU3MaNG+PnP/95pT8fAAAAAFQFPVQAAAAAyF+7RSg8IuL666+PwYMHp5qMJSUl8bvf/S66dOkSDRo0iIiIZDIZERGnnnpq1KtXL1q1ahVnnXVWTJ48ObVvy/u+tRIAAAAAdk96hdXnmmuuidWrV6fG/fv3j1GjRmVc36pVq7jtttvS5saNGxfLly+v8tp+9atfpY1/8YtfRP/+/TOuP/LII7eq/b//+7/Lveepp56KSZMmpcZNmjSJ22+/PYqKira5vqioKO64445o0qRJau7ll1+O5557rty7AAAAAKA66KECAAAAQH7abULhhYWF8Y9//CPOOuustIZjMpmMNWvWpI2XL18ea9eujWQymWpcbnnvvPPOi3vuuScrnwEAAAAA2Hl6hdVj8+bNceedd6bNXX755anfZyaDBg2KI444IjVevXp1PPDAA1Va27vvvhuvvfZaaly3bt0KPY175MiRUbdu3dR40qRJMWPGjO3uKRty//GPf1zuU5CaN28eI0aM2O45AAAAALCr6KECAAAAQH7abULhERG1a9eOu+++O+6///7o3LlzqgG5pUGZSCS2+on4sjm53377xf333x8333xz1KhRI2ufAQAAAADYeXqFVW/SpEmxdOnS1Lhjx44xYMCACu0dPnx42viRRx6pwsoiHn300bTxqaeeGvXr1y93X/369WPo0KFpc9ur7Ysvvohnnnkmbe773/9+hWosu+6pp56K0tLSCu0FAAAAgKqmhwoAAAAA+We3CoVvMWzYsJg+fXo89dRT8V//9V9x0EEHRVFRUeqbKpPJZBQWFkbHjh3j3HPPjfHjx8f7778fw4YNy3bpAAAAAEAV0iusOhMmTEgbf+Mb3yj3KeFfXftVEydOjJKSkmqrbfDgwRXeW7a2J554IuPasnV37tw52rVrV6F72rdvH506dUqNV69eHS+99FKF6wQAAACA6qCHCgAAAAD5Y7f+CschQ4bEkCFDUuO1a9fGypUro06dOtGoUaPsFQYAAAAA7FJ6hTvvrbfeShv37du3wntbtmwZ7du3j7lz50ZERGlpaUyfPj369Omz03Ulk8l45513dri2fv36pY3ffvvtSCaT2wy878zvYMtds2bNSjuvbCgdAAAAALJBDxUAAAAAdn85HwqfNWtWPPXUU6nx0UcfHV27dt3m2jp16kSdOnV2VWkAAAAAwC6kV1i9ZsyYkTbO9LvNpGvXrqlQ+JbzqiIUPm/evFi7dm1qXLdu3Wjbtm2F97dr1y7q1KmTOqOkpCQ+/vjjbZ5RFb+D7Z0HAAAAANVJDxUAAAAA8lvOh8KffvrpuOiiiyIiIpFIxJw5c7JcEQAAAACQDXqF1WfdunUxf/78tLk2bdpU6oyy62fOnLnTdW3rnMrWtWXPV8+ZOXPmNkPhO3tXdf0OAAAAAKAi9FABAAAAIL8VZLuA8qxZsyaSyWQkk8lo2bJltGvXLtslAQAAAABZoFdYfZYtWxbJZDI1rlmzZjRv3rxSZ7Rq1SptvGTJkiqprew5rVu3rvQZFa1tZ++qrt8BAAAAAFSEHioAAAAA5Lecf1J4s2bNIuLLb61s2bJllqsBAAAAALJFr7D6rFmzJm1cp06dSCQSlTqjbt262z1zR5U9p+w9FVHR2nb2rur6HSxZsiSWLl1aqT2zZ8+ukrsBAAAA2H3ooQIAAABAfsv5UPhXG5OrVq3KYiUAAAAAQDbpFVafsuHl4uLiSp9Ru3bt7Z65o3ZlbTt7V3X9Dm666aYYM2ZMlZwFAAAAQP7SQwUAAACA/FaQ7QLKc9hhh0XNmjUjmUzG3Llzo6SkJNslAQAAAABZoFdYfdavX582LioqqvQZtWrVShuvW7dup2raYlfWtrN3VdfvAAAAAAAqQg8VAAAAAPJbzofCGzduHEOGDImIiNLS0hg/fnyWKwIAAAAAskGvsPqUfSJ2aWlppc/44osvtnvmjtqVte3sXdX1OwAAAACAitBDBQAAAID8lvOh8IiI0aNHRyKRiIiISy+9NJYuXZrligAAAACAbNArrB716tVLG5d9YnZFlH0qdtkzd9SurG1n76qu38GIESNi2rRplfp55JFHquRuAAAAAHYveqgAAAAAkL92i1D417/+9bjyyisjmUzGJ598EkcddVTMmDEj22UBAAAAALuYXmH1KBteXrt2bSSTyUqdUVJSst0zd1TZc8reUxEVrW1n76qu30Hz5s2jW7dulfrZb7/9quRuAAAAAHYveqgAAAAAkL92i1B4RMTIkSPjT3/6UxQXF8d7770XPXv2jHPOOSeefvrpWLFiRbbLAwAAAAB2Eb3Cqte0adPU04MiIjZs2BBLliyp1BkLFy5MGzdv3rxKait7zoIFCyp9RkVr29m7qut3AAAAAACVoYcKAAAAAPmpRrYLqIiOHTumXteo8WXJpaWlcc8998Q999wTEV8+caVBgwZRs2bNCp+bSCRizpw5VVssAAAAAFBt9AqrR+3ataNt27Yxb9681Nz8+fOjRYsWFT5j/vz5aeMDDjigSmrr3Llz2vjjjz+u9Bll92SqrXPnzvGf//wnNS77mcpTXb8DAAAAAKgoPVQAAAAAyF+7RSh87ty5kUgkIplMRiKRSD2xJplMptasXr06Vq9eXalzv/rkGwAAAAAg9+kVVp8DDjggLRQ+ffr06NOnT4X3z5gxY6vzqkK7du2idu3asW7duoiIKCkpiXnz5kW7du0qtH/evHmxdu3a1Lhu3brRpk2bba4tW/P06dMrVWt1/Q4AAAAAoKL0UAEAAAAgfxVku4DKKNtU3NKw3JEfAAAAAGD3pVdY9Xr06JE2njRpUoX3fvLJJzF37tzUuGbNmtG1a9cqqSuRSET37t13uLZXX301bdy9e/eMf/ed+R1s666y5wEAAADArqKHCgAAAAD5Z7d4Unjbtm01FgEAAAAAvcJqdMIJJ8TVV1+dGj///POppwmV59lnn00bDxw4MOrVq1eltU2ePDk1fu655+K0006r0N7nnnsubfzNb34z49oBAwZE3bp1o6SkJCIiPvjggwo/lXzu3Lkxa9as1Lh+/foxYMCACtUIAAAAAFVFDxUAAAAA8tduEQr/6hNmAAAAAIA9l15h9enbt280bdo0li1bFhERH374YUycODEGDhxY7t7bb789bXzSSSdVaW0nnnhi/OpXv0qNH3zwwfj9739fbvB89erV8eCDD1a4tuLi4hg8eHD84x//SM3dcccdMWbMmHJrvOOOO9LGxxxzTBQVFZW7DwAAAACqkh4qAAAAAOSvgmwXAAAAAABA9hUUFMQ555yTNjdmzJhIJpPb3ffPf/4zXnnlldS4fv36ceqpp1Zpbd27d48+ffqkxmvWrIlrrrmm3H3XXHNN6qnfERGHHXZYdO3adbt7hg8fnjb+4x//GEuXLt3uniVLlsRNN9203XMAAAAAAAAAAABgZ+R8KHzTpk3x+eefp342bNiQ7ZIAAAAAgCzQK6x+o0aNSnv69ksvvRRXX311xvULFy6Mc889N23uwgsvjKZNm273nkQikfYzceLEcmv79a9/nTa+6qqr4uWXX864flu1/+Y3vyn3nuOPPz4OO+yw1Hj58uUxfPjwjP+/lZaWxvDhw2P58uWpuSOOOCKGDBlS7l0AAAAAUJX0UAEAAAAgv+V8KPzuu++OvfbaK/Xz1SfOAAAAAAB7Dr3C6te0adP45S9/mTY3evToGDFiRCxatCg1t3nz5njkkUeib9++MXfu3NR8y5Yt42c/+1m11HbMMcfE4MGDU+MNGzbEkCFD4oYbboi1a9em5ktKSuL666+PY445Ju0fvR533HExaNCgCt01duzYKCj43/b5448/HoMHD44333wzbd2UKVNi8ODB8cQTT6TmCgsLK/QUcwAAAACoanqoAAAAAJDfcj4U/umnn0YymYxkMhkNGzaMo446KtslAQAAAABZoFe4a4waNSpOOOGEtLmbb7452rZtG/vuu2/06tUrmjRpEt/61rdi/vz5qTW1a9eOBx54IBo1alRttf3lL3+JDh06pMbr16+Pn/70p9G0adP42te+Ft26dYumTZvGRRddFOvXr0+t23fffeOuu+6q8D2HH354XHnllWlzEydOjN69e0erVq3i4IMPjpYtW8bBBx8cL730Utq6a665Ju1J4wAAAACwq+ihAgAAAEB+y/lQeL169SIiIpFIRLt27bJcDQAAAACQLXqFu0ZBQUE8+OCD8Z3vfCdtftOmTfHhhx/G1KlTY+XKlWnvNWnSJJ588sno169ftdbWokWLePHFF+Oggw5Km1+3bl289957MX369LQweEREjx494sUXX4xmzZpV6q6RI0fGtddeG4WFhWnzixYtiilTpsQnn3ySNl9YWBjjxo2Liy++uFL3AAAAAEBV0UMFAAAAgPyW86HwffbZJ9slAAAAAAA5QK9w1ykuLo77778/xo8fHz169Mi4rm7dujFixIiYPn16DBgwYJfU1q5du3jttdfi6quvjpYtW2Zc17Jly7jmmmti8uTJ0aZNmx2662c/+1m88cYbcfzxx0dBwbbb6QUFBXHCCSfElClT4qc//ekO3QMAAAAAVUEPFQAAAADyW41sF1CeLl26REREMpmMjz/+OMvVAAAAAADZole4651yyilxyimnxOzZs2Py5MmxcOHCKC0tjUaNGkWXLl2iX79+UVxcXOlzk8nkTtVVVFQUI0eOjEsuuSSmTJkSb7/9dixZsiQiIpo3bx49evSIXr16ZQxyV0aPHj3iiSeeiGXLlsW//vWv+PDDD6OkpCTq1q0b++67b/Tr1y+aNm260/cAAAAAwM7SQwUAAACA/JbzofBu3bpFt27d4r333ovPPvssJk+eHIceemi2ywIAAAAAdjG9wuzZb7/9Yr/99st2GVspKCiIPn36RJ8+far9rqZNm8bJJ59c7fcAAAAAwI7SQwUAAACA/Lbzj0nZBX74wx+mXl922WVZrAQAAAAAyCa9QgAAAACAzPRQAQAAACB/7Rah8BEjRkS/fv0imUzGc889F5dcckm2SwIAAAAAskCvEAAAAAAgMz1UAAAAAMhfu0UovLCwMB5//PE4/PDDI5lMxrhx46J///4xceLEbJcGAAAAAOxCeoUAAAAAAJnpoQIAAABA/qqR7QIq4te//nVERBx55JExa9as+PTTT+PVV1+NQYMGRYsWLeLggw+ODh06RIMGDaJmzZqVOvt//ud/qqNkAAAAAKAa6BUCAAAAAGSmhwoAAAAA+Wu3CIVffvnlkUgkUuNEIhHJZDIiIhYvXhwTJkzY4bM1KQEAAABg96FXCAAAAACQmR4qAAAAAOSv3SIUvi1fbVruiGQyudNnAAAAAADZp1cIAAAAAJCZHioAAAAA5IfdJhS+5ZsqAQAAAIA9m14hAAAAAEBmeqgAAAAAkJ92i1D4iy++mO0SAAAAAIAcoFcIAAAAAJCZHioAAAAA5K/dIhR+5JFHZrsEAAAAACAH6BUCAAAAAGSmhwoAAAAA+asg2wUAAAAAAAAAAAAAAAAAAACQmVA4AAAAAAAAAAAAAAAAAABADhMKBwAAAAAAAAAAAAAAAAAAyGFC4QAAAAAAAAAAAAAAAAAAADlMKBwAAAAAAAAAAAAAAAAAACCH1ch2ARXx8ssvV9vZ/fv3r7azAQAAAICqpVcIAAAAAJCZHioAAAAA5K/dIhQ+YMCASCQSVX5uIpGIjRs3Vvm5AAAAAED10CsEAAAAAMhMDxUAAAAA8tduEQrfIplMZrsEAAAAACAH6BUCAAAAAGSmhwoAAAAA+We3CYXvaIOy7DdeanQCAAAAwO5NrxAAAAAAIDM9VAAAAADIT7tFKPyyyy6r9J61a9fG0qVL4/XXX4/33nsvIr5sWO63335xxhlnVHWJAAAAAMAuoFcIAAAAAJCZHioAAAAA5K+8DYV/1bRp0+LSSy+Nxx9/PObMmROzZ8+OO++8M2rU2C0+PgAAAADw/+kVAgAAAABkpocKAAAAAPmrINsF7Apf+9rX4tFHH41LL700kslk3HffffG9730v22UBAAAAALuYXiEAAAAAQGZ6qAAAAACQu/aIUPgWV1xxRQwZMiTVqLz//vuzXRIAAAAAkAV6hQAAAAAAmemhAgAAAEDu2aNC4RERl112WUREJJPJ1GsAAAAAYM+jVwgAAAAAkJkeKgAAAADklj0uFH7YYYdF48aNIyJizpw5MXXq1CxXBAAAAABkg14hAAAAAEBmeqgAAAAAkFv2uFB4RETbtm1Tr998880sVgIAAAAAZJNeIQAAAABAZnqoAAAAAJA79shQeEHB/37sJUuWZLESAAAAACCb9AoBAAAAADLTQwUAAACA3LHHhcI3b94cH374YWpcXFycxWoAAAAAgGzRKwQAAAAAyEwPFQAAAAByyx4XCn/iiSdi5cqVqfHee++dvWIAAAAAgKzRKwQAAAAAyEwPFQAAAAByyx4VCp8zZ078+Mc/jkQikZo7/PDDs1gRAAAAAJANeoUAAAAAAJnpoQIAAABA7sn7UPimTZvi7bffjksvvTR69uwZixYtimQyGYlEIr7+9a9HmzZtsl0iAAAAALAL6BUCAAAAAGSmhwoAAAAAua1GtguoiI4dO+7QvnXr1sVnn30WGzZsiIhINScjIgoLC+Paa6+tshoBAAAAgOqnVwgAAAAAkJkeKgAAAADkr90iFD537txIJBKRTCZ3+IxEIpE6o7CwMG699dY47LDDqrBKAAAAAKC66RUCAAAAAGSmhwoAAAAA+Wu3CIVvseVbJytjS2Nzy38POeSQuPHGG6NPnz5VWhsAAAAAsOvoFQIAAAAAZKaHCgAAAAD5Z7cIhbdt27bSDcpEIhHFxcXRoEGDaNeuXfTq1SuOO+64OPDAA6upSgAAAACguukVAgAAAABkpocKAAAAAPlrtwiFz507N9slAAAAAAA5QK8QAAAAACAzPVQAAAAAyF8F2S4AAAAAAAAAAAAAAAAAAACAzITCAQAAAAAAAAAAAAAAAAAAcphQOAAAAAAAAAAAAAAAAAAAQA4TCgcAAAAAAAAAAAAAAAAAAMhhQuEAAAAAAAAAAAAAAAAAAAA5bLcIhf/rX/+KwsLC1M+LL764Q+e88MILqTNq1KgRU6ZMqeJKAQAAAIDqpFcIAAAAAJCZHioAAAAA5K/dIhT+5z//OZLJZCSTyejTp08MHDhwh8456qijomfPnpFMJmPz5s1x6623VnGlAAAAAEB10isEAAAAAMhMDxUAAAAA8lfOh8I3b94cTz75ZCQSiUgkEnHGGWfs1Hlnn312REQkEol47LHHqqJEAAAAAGAX0CsEAAAAAMhMDxUAAAAA8lvOh8Lffffd+OyzzyKZTEZExPHHH79T523Zn0wm49NPP42ZM2fudI0AAAAAQPXTKwQAAAAAyEwPFQAAAADyW86HwmfMmJF63ahRo+jYseNOnbfvvvtGo0aNUuP33ntvp84DAAAAAHYNvUIAAAAAgMz0UAEAAAAgv+V8KHzx4sUREZFIJKJVq1ZVcmbr1q1TrxcuXFglZwIAAAAA1UuvEAAAAAAgMz1UAAAAAMhvOR8KX7t2bep13bp1q+TMr56zZs2aKjkTAAAAAKheeoUAAAAAAJnpoQIAAABAfsv5UHjDhg1Tr5cvX14lZ65YsSL1uk6dOlVyJgAAAABQvfQKAQAAAAAy00MFAAAAgPyW86HwZs2aRUREMpmMjz/+ONatW7dT561duzbmzZsXiUQi7XwAAAAAILfpFQIAAAAAZKaHCgAAAAD5LedD4QcccEDqdWlpaTz77LM7dd4zzzwTpaWlkUwmIyJi33333anzAAAAAIBdQ68QAAAAACAzPVQAAAAAyG85Hwrv3r17NG/ePBKJRCSTybjiiit26rzf/OY3qW+tbNSoURxyyCFVUSYAAAAAUM30CgEAAAAAMtNDBQAAAID8lvOh8IiIk08+OfVNk1OnTo2LL754h865+OKLY+rUqRERkUgk4uSTT041LAEAAACA3KdXCAAAAACQmR4qAAAAAOSv3SIUfumll0ZRUVHq2ytvuOGGOPvss+Pzzz+v0P7PP/88zjrrrLjhhhtSZ9SsWTP++7//u5orBwAAAACqkl4hAAAAAEBmeqgAAAAAkL92i1B4mzZtYvTo0ZFMJlNNxnvvvTfatm0bF1xwQTz99NOxbNmytD3Lli2Lp59+Oi644IJo165d3HfffZFMJlNnjBo1Kjp06JClTwQAAAAA7Ai9QgAAAACAzPRQAQAAACB/1ch2ARV12WWXxbRp0+Khhx5KNSo///zz+OMf/xh//OMfIyIikUhEnTp1Yu3atZFMJlN7t7zesu/UU0+NMWPGZOVzAAAAAAA7R68QAAAAACAzPVQAAAAAyE+7xZPCt7j//vvjwgsvTH37ZCKRiIhIfSPl5s2bY82aNbF58+bUXESk1kVE/OxnP4u//vWvWakfAAAAAKgaeoUAAAAAAJnpoQIAAABA/tmtQuE1atSIcePGxVNPPRWHHnroVo3Isj8R/9vAPPzww+PZZ5+NsWPHRmFhYTY/BgAAAACwk/QKAQAAAAAy00MFAAAAgPxTI9sF7IghQ4bEkCFD4vXXX49nn302XnnllZgzZ06sWLEiVq9eHfXr14/GjRtHp06d4ogjjohjjjkmevbsme2yAQAAAIAqplcIAAAAAJCZHioAAAAA5I/dMhS+RZ8+faJPnz7ZLgMAAAAAyDK9QgAAAACAzPRQAQAAAGD3V5DtAgAAAAAAAAAAAAAAAAAAAMhMKBwAAAAAAAAAAAAAAAAAACCHCYUDAAAAAAAAAAAAAAAAAADksBrZLqCi5s+fn3q91157Rf369St9xurVq+Ozzz5Ljdu2bVsltQEAAAAAu45eIQAAAABAZnqoAAAAAJCfdosnhT/11FPRoUOH1M/s2bN36JwPPvgg2rdvnzpn4sSJVVsoAAAAAFCt9AoBAAAAADLTQwUAAACA/LVbhMJvvfXWSCaTkUwm46ijjoqePXvu0Dm9e/eOI488MnXWbbfdVsWVAgAAAADVSa8QAAAAACAzPVQAAAAAyF85HwrfsGFDPPfcc5FIJCKRSMRpp522U+edeeaZqddPPfVUJJPJnS0RAAAAANgF9AoBAAAAADLTQwUAAACA/JbzofC33347SkpKUs3EIUOG7NR5xxxzTOr1ypUrY9q0aTt1HgAAAACwa+gVAgAAAABkpocKAAAAAPkt50PhM2bMSL1u1qxZtGrVaqfOa9WqVTRr1iw1nj59+k6dBwAAAADsGnqFAAAAAACZ6aECAAAAQH7L+VD40qVLIyIikUjE3nvvXSVn7rPPPqnXixcvrpIzAQAAAIDqpVcIAAAAAJCZHioAAAAA5LecD4WvX78+9bq4uLhKzqxVq1bqdUlJSZWcCQAAAABUL71CAAAAAIDM9FABAAAAIL/lfCi8cePGqdfLli2rkjOXL1+eel2/fv0qORMAAAAAqF56hQAAAAAAmemhAgAAAEB+y/lQeNOmTSMiIplMxvz582PVqlU7dd7KlStj3rx5kUgkIiKiWbNmO10jAAAAAFD99AoBAAAAADLTQwUAAACA/JbzofDu3btHREQikYhNmzbF448/vlPnPfbYY7Fp06ZIJpMREdGlS5edrhEAAAAAqH56hQAAAAAAmemhAgAAAEB+y/lQ+P777x9t2rSJiC+/vXLMmDGxYcOGHTqrtLQ0rrjiitS3VrZo0SIOOuigKqsVAAAAAKg+eoUAAAAAAJnpoQIAAABAfsv5UHhExHe+851IJpORSCTiww8/jLPOOmuHzjnrrLNizpw5qbOGDRtWxZUCAAAAANVJrxAAAAAAIDM9VAAAAADIX7tFKHzkyJFRr169iPjy2ysffPDBGDBgQHz44YcV2j9nzpwYMGBAjB8/PvWtlXXq1InRo0dXW80AAAAAQNXTKwQAAAAAyEwPFQAAAADyV41sF1ARTZo0ibFjx8aPfvSjSCQSkUwm4+WXX47OnTvHscceG8cdd1wcfPDB0bx586hXr16sWbMmlixZEm+88UY8+eST8dRTT8XmzZsjmUxGREQikYixY8dG8+bNs/zJAAAAAIDK0CsEAAAAAMhMDxUAAAAA8tduEQqPiDjvvPNixowZ8fvf/z717ZObNm2KCRMmxIQJE7a7N5lMRiKRSDU4L7roojj//PN3RdkAAAAAQBXTKwQAAAAAyEwPFQAAAADyU0G2C6iM66+/PsaNGxc1atRINR4jvmxCZvqJiFRzsqioKG688ca49tprs/kxAAAAAICdpFcIAAAAAJCZHioAAAAA5J/dKhQeEXHhhRfGm2++Gd/5zneioKAg1YiMiNS3U25pXkZ82cAsLCyMM888M95888348Y9/nI2yAQAAAIAqplcIAAAAAJCZHioAAAAA5Jca2S5gR3Tr1i3uu+++uO666+Kf//xnvPLKKzFnzpxYsWJFrF69OurXrx+NGzeOTp06xRFHHBGDBg2K5s2bZ7tsAAAAAKCK6RUCAAAAAGSmhwoAAAAA+WO3DIVvsffee8cZZ5wRZ5xxRrZLAQAAAACySK8QAAAAACAzPVQAAAAA2P0VZLsAAAAAAAAAAAAAAAAAAAAAMhMKBwAAAAAAAAAAAAAAAAAAyGE1sl1AZc2bNy9mzJgRK1asiBUrVsTq1aujfv360bhx42jcuHF06dIl2rVrl+0yAQAAAIBqplcIAAAAAJCZHioAAAAA5JecD4Vv3rw5xo8fHw899FC8+uqr8cknn5S7Z5999ol+/frF//k//yeGDh0aBQUeiA4AAAAAuzu9QgAAAACAzPRQAQAAACC/5Wz3buPGjXHttddGhw4d4rTTTovx48fHokWLIplMlvuzaNGiGD9+fJx++unRvn37uPbaa2Pjxo3Z/kgAAAAAwA7QKwQAAAAAyEwPFQAAAAD2DDn5pPAPPvggTj/99Jg6dWokk8nUfCKRqPAZW/YtWLAgRo0aFffff3/ce++9ccABB1R5vbuzmTNnxttvvx0LFiyItWvXRu3ataNFixax//77x0EHHRS1atXa4bPXr18fkyZNivfffz8+++yzKCoqitatW8ehhx4aHTt2rMJPETFnzpx47bXXYsGCBVFaWhp77bVXHHDAAdG3b98oLi6u0rsAAAAA2HX0CgEAAAAAMtNDBQAAAIA9R86Fwh9++OE4++yzY926dZFMJlONyS3fSrlFQUFBNGjQIOrWrRslJSXx+eefx+bNm9PO+ureqVOnRu/eveOuu+6KoUOH7roPlINWr14dN954Y9x2223x0UcfZVxXVFQUhxxySHz729+OCy+8sMLnL126NMaMGRN33XVXlJSUbHNN796941e/+lWcdNJJla7/qx555JG44oor4s0339zm+/Xq1YtzzjknLrvssmjatOlO3QUAAADArqVXCAAAAACQmR4qAAAAAOxZcioU/vjjj8ewYcNi06ZNkUgkIpFIpBqTvXr1ilNOOSV69+4dPXv2jGbNmm21f+nSpTF16tSYMmVKPPTQQ6mg8JZm5bp16+KMM86IWrVqxYknnrjrPlgOeeKJJ+Lcc8+NTz/9tNy1paWl8a9//StmzZpV4VD4xIkTY+jQobFs2bLtrpsyZUqcfPLJcfbZZ8ett94aRUVFFTp/iy+++CKGDx8e995773bXrVmzJv7whz/E3//+9xg/fnz079+/UvcAAAAAkB16hQAAAAAAmemhAgAAAMCepyDbBWwxZ86cOOOMM1INyogvv3Hy5JNPjnfeeSfeeOONGD16dAwePHibDcqIiGbNmsXgwYNj9OjR8cYbb8Q777wTJ598cqrRmUgkYuPGjXHmmWfG7Nmzd9lnyxXjxo2LE088catAeHFxcXTs2DEOOeSQOPDAA3f4idr/+te/4rjjjtsqEN6oUaPo2bNntG/fPgoLC9Pe+8tf/hKnnXZa2reSlmfz5s0xbNiwrQLhhYWF0aFDh+jRo0c0bNgw7b2lS5fGscceG//+978r+akAAAAA2NX0CgEAAAAAMtNDBQAAAIA9U86Ews8777xYs2ZN6tsqGzRoEI8//ng8/PDD8bWvfW2Hzvza174WDz/8cDz22GPRoEGDiPiyUblmzZo477zzqrL8nHf77bfHxRdfnBa+PvbYY+Opp56KlStXxpw5c2Ly5MnxzjvvxNKlS2PhwoVxzz33xCmnnFKhp3h/9tlnMWzYsFi3bl1qrl27dvHII4/EihUr4s0334yPPvoo5s6du9Xv/uGHH45x48ZV+LOMHTs2Hn300bS5888/P+bPnx8ffvhhTJ06NVasWBEPP/xwtG3bNrVm7dq1ceqpp8aqVasqfBcAAAAAu55eIQAAAABAZnqoAAAAALBnyolQ+IsvvhgvvPBCqkHZrFmzeOGFF+L444+vkvNPOOGEeOGFF6JJkyapuYkTJ8aLL75YJefnutmzZ8dPfvKT1LhmzZpx3333xZNPPhnHHHNM1KpVa6s9LVu2jDPPPDPGjx8fb7/9drl3jB07NhYtWpQad+jQISZNmhQnnXRS6ptIIyJat24df/rTn+K3v/1t2v5f//rX8dlnn5V7z/Lly7fae+WVV8bNN98cLVu2TM0VFBTEt771rZg0aVK0b98+Nb9gwYK47rrryr0HAAAAgOzQKwQAAAAAyEwPFQAAAAD2XDkRCv/zn/8cERHJZDISiUTccccd0bNnzyq9o2fPnnHHHXek7vjqvfnuhz/8Yaxfvz41vvfee+O0006r8P699tpru+8vXbo0brzxxrS5W2+9NS2kXdbo0aOjf//+qfGqVavi2muvLbeWa665JlavXp0a9+/fP0aNGpVxfatWreK2225Lmxs3blwsX7683LsAAAAA2PX0CgEAAAAAMtNDBQAAAIA9V9ZD4Rs3bowJEyZEIpGIRCIRJ598cpV9Y2VZJ5xwQpx88smRTCYjmUzGhAkTYuPGjdVyV6549NFH076hc+jQoTF06NAqveNvf/tbrFmzJjXu379/DBo0aLt7EolEXHbZZWlzW5rImWzevDnuvPPOtLnLL7887Unk2zJo0KA44ogjUuPVq1fHAw88sN09AAAAAOx6eoUAAAAAAJnpoQIAAADAni3rofC33norSkpKUmHg4cOHV+t95557bur12rVrY+rUqdV6X7bdcsstaeOyQeyq8Oijj6aNK/o3HDhwYHTo0CE1Xrx4cfznP//JuH7SpEmxdOnS1Lhjx44xYMCACt1VtqZHHnmkQvsAAAAA2HX0CgEAAAAAMtNDBQAAAIA9W9ZD4TNnzky9LioqisGDB1frfYMHD45atWqlni791fvzzcKFC+OZZ55JjXv06BHdunWr0jvWrFkTL7/8ctpcRf+GiUQijj766LS5J554IuP6CRMmpI2/8Y1vlPuU8K+u/aqJEydGSUlJhfYCAAAAsGvoFQIAAAAAZKaHCgAAAAB7tqyHwj/99NPU63322Sdq1KhRrffVqFEjWrZsmfqmzK/en2+efvrp2LRpU2o8cODAKr/jvffeiw0bNqTGHTp0iL333rvC+/v165c2fuuttzKuLfte3759K3xPy5Yto3379qlxaWlpTJ8+vcL7AQAAAKh+eoUAAAAAAJnpoQIAAADAni3rofB169ZFxJdPjW7evPkuubNp06ap1+vXr98ld2bD66+/njY+6KCDUq+nTp0aF1xwQRx00EGx1157RZ06daJ9+/bxjW98I6699tpYuHBhhe6YMWNG2rhr166VqrHs+rLnZesuAAAAAHY9vUIAAAAAgMz0UAEAAABgz5b1UHhxcXHq9fLly3fJnStWrEi9rlWr1i65MxvKhsI7duwYa9asieHDh0evXr3ixhtvjHfeeSdWrlwZ69ati3nz5sXzzz8fP//5z6NTp07xy1/+Mu0p4Nsyc+bMtHGbNm0qVWPZ9fPmzdtm43jdunUxf/78Kr2rbO0AAAAAZJdeIQAAAABAZnqoAAAAALBnq5HtApo1axYREclkMj755JNIJpORSCSq7b7NmzfHokWLUndsuT8fzZ49O21cUFAQ/fv3j6lTp5a7d926dXHllVfG66+/Hg8//HDUr19/m+uWLFmSNm7dunWlamzRokXUqFEjNm7cGBFf/n2WL18erVq1Slu3bNmySCaTqXHNmjUr/U2nZc8sW/uOWrJkSSxdurRSe8r+bQAAAADQKwQAAAAA2B49VAAAAADYs2U9FN6pU6fU63Xr1sWLL74YRx11VLXdN3HixFi3bl1ERCQSibT788nmzZtj9erVaXMXXHBBKhCeSCTihBNOiOOOOy5at24dJSUlMXXq1Ljnnnti0aJFqT3PP/98nHPOOfHQQw9t8541a9akjevWrVupOhOJRNSuXTut1rJnbmuuTp06lW5ml61tW/fsiJtuuinGjBlTJWcBAAAA7Mn0CgEAAAAAMtNDBQAAAIA9W0G2C+jVq1fUqlUrFfD9y1/+Uq333XXXXanXRUVF0bt372q9L1tWrVqV9mTtiIg333wzIiKaNGkSL730Ujz22GNx/vnnxwknnBDDhg2Lq666KmbOnBmnn3562r6HH34449+lbLC6uLi40rXWrl17u2fuynsAAAAAyB69QgAAAACAzPRQAQAAAGDPlvVQeK1ateIb3/hGJJPJSCaT8de//jVeffXVarnrlVdeiXvvvTcSiUQkEok4+uijo1atWtVyV7ZlCjwXFhbGhAkT4ogjjtjm+/Xq1Yt77rknBg8enDb/u9/9bquQeUTE+vXr08ZFRUWVrrXs32DLN4tm4x4AAAAAskevEAAAAAAgMz1UAAAAANizZT0UHhExfPjwiIhIJBKxefPmOPPMM2PevHlVesfcuXPj7LPPTjVDIyLOPffcKr0jl2R6kva5554bhx566Hb3FhQUxM033xwFBf/7v8fMmTPjpZdeKvee0tLSStf6xRdfbPfMXXnPjhgxYkRMmzatUj+PPPJIldwNAAAAkG/0CgEAAAAAMtNDBQAAAIA9V06Ewk866aTo1atXRHzZqJw3b14cccQR8dZbb1XJ+VOnTo3+/fvH/PnzU99a2aNHjzjppJOq5PxcVK9evW3O/+AHP6jQ/o4dO8bRRx+dNretUHjZe8o+0bsiyj6xe1u176p7dkTz5s2jW7dulfrZb7/9quRuAAAAgHyjVwgAAAAAkJkeKgAAAADsuXIiFB4Rccstt0SNGjUi4stG5YIFC+KQQw6Jiy++OFasWLFDZ65YsSIuvvjiOPTQQ2PBggUREZFMJqNGjRpxyy23VFntuah27dpRWFiYNle/fv3o2bNnhc848sgj08ZvvPHGVmvKBqtLSkoqUeWXf48dCYWvXbs29Q2kFVW2tqoKhQMAAABQtfQKAQAAAAAy00MFAAAAgD1TzoTCe/XqFTfeeGMq6JtIJGLjxo1xww03RMuWLWPo0KHxt7/9LWbNmrXdc2bPnh1/+9vfYujQodGyZcu44YYbYuPGjZFIJFLn3nDDDdG7d+9q/0zZ1rx587TxfvvtFwUFFf+Td+7cOW28ZMmScu/Y0gyuqE8//TQ2btyYGhcUFETTpk23Wte0adPU3zAiYsOGDdusZ3sWLlyYNi5bOwAAAAC5Qa8QAAAAACAzPVQAAAAA2DPVyHYBX/XDH/4wSkpK4pJLLomILxuKyWQySktL4+GHH46HH344IiLq1q0bLVq0iIYNG0bdunWjpKQkVq1aFUuWLIk1a9akzvtqwzOZTEYikYirr746zj///F3/4bKgS5cu8cknn6TGDRo0qNT+sus/++yzrdaUDY7Pnz+/UneUXd+uXbsoLi7eal3t2rWjbdu2MW/evLS9LVq02OG7DjjggErVCgAAAMCuo1cIAAAAAJCZHioAAAAA7HlyKhQeEXHRRRfFQQcdFN/97ndj4cKFqW+c3NJwjIhYs2ZNqhm5pQG5LV/du88++8Tdd98dRx99dDV/gtzRtWvXeOGFF1LjL774olL7169fnzauU6fOVmvKBqunT59eqTtmzJix3fPKvvfVUPj06dOjT58+1XIXAAAAANmnVwgAAAAAkJkeKgAAAADsWQqyXcC2HHXUUfHOO+/EeeedF8XFxWnfQFn2Z3vzyWQyatWqFT/84Q/j3Xff3eMalL169Uobf/rpp5Xav2TJkrRxkyZNtlrTrVu3qFmzZmo8d+7ctKeTl+fVV19NG/fo0SPj2rLvTZo0qcL3fPLJJzF37tzUuGbNmtG1a9cK7wcAAAAgO/QKAQAAAAAy00MFAAAAgD1HTobCIyL22muvuPnmm+Pjjz+O3/72t9G7d+8oLCyMZDJZ7k9BQUH06tUrfvvb38bHH38cf/rTn6Jx48bZ/ki73PHHHx8FBf/7J/7oo49ixYoVFd4/ZcqUtHHnzp23WlO/fv3o379/2txzzz1XofOTyWQ8//zzaXPf/OY3M64/4YQT0sbPP/98xm8tLevZZ59NGw8cODDq1atXob0AAAAAZJdeIQAAAABAZnqoAAAAALBnqJHtAsrTuHHjGD16dIwePTpKSkpi8uTJ8f7778eKFStixYoVsXr16qhfv340btw4GjduHJ07d47DDjss6tatm+3Ss6558+bRr1+/eOWVV1JzDz/8cJx77rnl7t24cWP84x//SJsbMGDANteeeOKJ8c9//jM1vv322+Pss88u944XX3wxPvroo9S4RYsWceihh2Zc37dv32jatGksW7YsIiI+/PDDmDhxYgwcOLDcu26//fa08UknnVTuHgAAAAByi14hAAAAAEBmeqgAAAAAkN9yPhT+VXXr1o2jjjoqjjrqqGyXsts477zz0kLhY8eOjbPOOitq1aq13X233nprLF68ODVu0KBBDBkyZJtrv/Od78Qvf/nLKCkpiYiIl19+OV544YXt/p2SyWSMGTMmbe573/te2pPNyyooKIhzzjknrr322tTcmDFjYsCAAZFIJDLu++c//5n2O6hfv36ceuqpGdcDAAAAkPv0CgEAAAAAMtNDBQAAAID8kzmBS1447bTT4sADD0yNP/jggzjvvPNi8+bNGfdMnjw5Ro4cmTY3YsSIaNiw4TbXN2/ePH7yk5+kzZ177rmxaNGijHdceeWV8fLLL6fGDRs2jJ///Ofb/SwREaNGjYp69eqlxi+99FJcffXVGdcvXLhwqyejX3jhhdG0adNy7wIAAAAAAAAAAAAAAAAAgFwgFJ7nCgoKYty4cWlP0r777rtjyJAhMWXKlLS1q1atiuuuuy6OPvroWLNmTWp+//33j1/+8pfbvWfkyJGx9957p8YfffRR9O3bNx577LFIJpOp+QULFsT5558fl156adr+Sy+9NBo3blzu52natOlWtYwePTpGjBiRFkLfvHlzPPLII9G3b9+YO3duar5ly5bxs5/9rNx7AAAAAAAAAAAAAAAAAAAgV9TIdgFUv0GDBsWVV14Zv/jFL1Jzzz//fBx88MGx9957R+vWraOkpCTmzJkTpaWlaXubNGkS48ePj/r162/3jsaNG8ff//73GDJkSKxfvz4iIubNmxcnnXRSNGrUKDp06BArV66M+fPnx6ZNm9L2nnTSSXHJJZdU+POMGjUqJk2aFE888URq7uabb45bbrkl2rVrFw0bNoyPPvooVq5cmbavdu3a8cADD0SjRo0qfBcAAAAAAAAAAAAAAAAAAGSbJ4XvIUaNGhW///3vo2bNmmnzixcvjjfeeCNmzJixVSC8c+fO8e9//zsOPPDACt3Rv3//mDBhwlZP/F65cmVMnTo1Pvroo60C4aeffnr8/e9/T3uSeXkKCgriwQcfjO985ztp85s2bYoPP/wwpk6dulUgvEmTJvHkk09Gv379KnwPAAAAAAAAAAAAAAAAAADkAqHwPch//dd/xTvvvBPDhg3bKhz+VR06dIgbbrgh3nnnnejUqVOl7jjqqKNi+vTp8aMf/Sjq1KmTcV3Pnj3joYceinvvvTdq1apVqTsiIoqLi+P++++P8ePHR48ePTKuq1u3bowYMSKmT58eAwYMqPQ9AAAAAAAAAAAAAAAAAACQbTWyXQC71gEHHBB/+9vf4vPPP49JkybFrFmzYtWqVVGvXr1o0aJF9OrVKzp37rxTd7Ro0SJuuumm+L//9//GpEmTYsaMGbFy5cooKiqKVq1axaGHHhr77bdflXyeU045JU455ZSYPXt2TJ48ORYuXBilpaXRqFGj6NKlS/Tr1y+Ki4ur5C4AAAAAAAAAAAAAAAAAAMgGofA9VIMGDeKYY46JY445ptruqF27dgwaNCgGDRpUbXdssd9++1VZ0BwAAAAAAAAAAAAAAAAAAHJJQbYLAAAAAAAAAAAAAAAAAAAAIDOhcAAAAAAAAAAAAAAAAAAAgBwmFA4AAAAAAAAAAAAAAAAAAJDDhMIBAAAAAAAAAAAAAAAAAABymFA4AAAAAAAAAAAAAAAAAABADhMKBwAAAAAAAAAAAAAAAAAAyGFC4QAAAAAAAAAAAAAAAAAAADlMKBwAAAAAAAAAAAAAAAAAACCHCYUDAAAAAAAAAAAAAAAAAADkMKFwAAAAAAAAAAAAAAAAAACAHCYUDgAAAAAAAAAAAAAAAAAAkMOEwgEAAAAAAAAAAAAAAAAAAHKYUDgAAAAAAAAAAAAAAAAAAEAOEwoHAAAAAAAAAAAAAAAAAADIYULhAAAAAAAAAAAAAAAAAAAAOaxGtgsAAAAAAAAAAAAAgO0pLS2N999/P+bOnRsLFy6M1atXx4YNG6JBgwbRpEmT6N69e3Tp0iUKCwur5L6NGzfG5MmTY9q0abF8+fIoLCyMffbZJ3r37h3dunWrkju2WLhwYfz73/+OefPmxbp166JBgwax//77x+GHHx716tWr0rsAAAAA2H0JhQMAAAAAAAAAAACQc8aPHx/PP/98vPrqq/H+++/Hxo0bt7u+YcOGcdppp8WFF14YBxxwwA7duWbNmrjqqqvi5ptvjhUrVmxzTefOnWPUqFFxzjnnRCKR2KF7IiJeeumluPzyy2PixInbfL+oqCiGDRsWv/71r6N9+/Y7fA8AAAAA+aEg2wUAAAAAAAAAAAAAQFk//elP489//nNMmzat3EB4RMSqVaviT3/6U3Tv3j0uv/zySCaTlbrv3Xffje7du8dvf/vbjIHwiIiZM2fG97///Tj22GNj1apVlbojIiKZTMbIkSNjwIABGQPhEV8+Hf2ee+6Jr33ta/HQQw9V+h4AAAAA8otQOAAAAAAAAAAAAAC7heLi4th///2jT58+0bt372jXrt1WT+vesGFDjBkzJs4999wKnztz5sw46qij4qOPPkqbr1evXnTv3j06deoUNWvWTHvvmWeeiWOPPTbWr19fqc9wwQUXxNixY9PmEolEtGnTJnr16hVNmzZNe6+kpCSGDRsW//jHPyp1DwAAAAD5RSgcAAAAAAAAAAAAgJzUsmXL+MEPfhD33HNPzJ49O0pKSmLmzJnx2muvxRtvvBFz586N5cuXxy233BKtW7dO23vHHXfEnXfeWe4dGzdujKFDh8ayZctSc40bN4677747VqxYEW+//XZ88MEHsXjx4rj00kujoOB///ntv//97xg5cmSFP88DDzwQf/jDH9LmTjnllJg5c2bMnz8/pkyZEkuXLo3nn38+unfvnlqzadOm+O53vxtz586t8F0AAAAA5BehcAAAAAAAAAAAAAByzpNPPhkLFiyIW265Jc4888zYd9990wLZW+y1117xgx/8IN55553o1atX2nuXXnppbN68ebv33HHHHfHuu++mnffKK6/E2WefnfZ08MaNG8dvfvObuOeee9L233zzzTFr1qxyP09paWmMGjUqbe7888+PBx98MDp16pQ2P2jQoHj55Zfj4IMPTs2tXr06LrvssnLvAQAAACA/CYUDAAAAAAAAAAAAkHO6d+8eiUSiwuv32muv+Otf/5q255NPPolXX301457S0tL4zW9+kzZ37bXXRteuXTPuOf300+PMM89MjTdu3BiXX355ufXdfvvtaU/67tSpU4wbNy7jZ2zYsGHcfffdUVRUlJq799574/333y/3LgAAAADyj1A4AAAAAAAAAAAAAHmhS5cu0bt377S5GTNmZFz/zDPPxMcff5wat2/fPr73ve+Ve8/ll1+eFuZ+8MEHY9WqVdvdc9ttt6WNR48eHcXFxdvd07Vr1xg2bFhqvGnTprjzzjvLrQ8AAACA/CMUDgAAAAAAAAAAAEDe2HfffdPGy5Yty7j20UcfTRt/73vfq9DTyffdd9848sgjU+MNGzbEk08+mXH9ggUL4s0330yN69WrF6eeemq590REDB8+fLs1AwAAALBnEAoHAAAAAAAAAAAAIG+sX78+bdyoUaOMaydMmJA2Hjx4cIXv+cY3vpE2fuKJJyp8T79+/aJu3boVuqdfv35Rp06d1HjmzJkxa9asCtcJAAAAQH4QCgcAAAAAAAAAAAAgLySTyXj99dfT5nr37r3NtZ9++mksXrw4Na5Vq1b06tWrwnf169cvbfzWW29lXFv2vb59+1b4nho1asQhhxxS4bsAAAAAyE9C4QAAAAAAAAAAAADkhTvuuCMWLVqUGh9wwAFbBaq3mDFjRtp4v/32i6Kiogrf1bVr17Tx7NmzY+PGjRW6q+zeyt5V9jwAAAAA8p9QOAAAAAAAAAAAAAC7vbvvvjtGjBiRGhcUFMQf/vCHSCQS21w/c+bMtHGbNm0qdV+zZs2iuLg4NS4tLY2PPvqoWu4qu77seQAAAADkvxrZLgAAAAAAAAAAAAAAyvPBBx/E/PnzU+MNGzbEZ599FtOmTYtHH300pk+fnnqvqKgobrnllhg0aFDG85YsWZI2bt26daVratmyZXz44YdpZ3bq1GmrdUuXLt2pu1q1apU2Llv7zliyZMlW9ZVn9uzZVXY/AAAAABUjFA4AAAAAAAAAAABAzrvpppvihhtu2O6aRCIRxxxzTFx55ZVx0EEHbXftmjVr0sZ169atdE1l95Q9MyJi3bp1sWnTpp26qyL37KibbropxowZU2XnAQAAAFA9hMIBAAAAAAAAAAAAyAtDhw6NCy64oNxAeMTWweri4uJK31e7du3tnplprrJ3VeQeAAAAAPJbQbYLAAAAAAAAAAAAAICq8MADD8Thhx8e/fv3j9mzZ2937fr169PGRUVFlb6vVq1aaeN169aVe8+O3FWRewAAAADIb54UDgAAAAAAAAAAAEDOu/766+P6669PjdetWxfLly+Pt99+O/7xj3/EfffdlwpLv/LKK9GnT5947rnn4uCDD97meWWf1l1aWlrpmr744ovtnplprrS0tFJPC6/IPTtqxIgRMXTo0ErtmT17dpx88slVVgMAAAAA5RMKBwAAAAAAAAAAAGC3U7t27WjdunW0bt06jj/++PjFL34RQ4cOjbfeeisiIlauXBknn3xyTJs2LRo1arTV/nr16qWNt/VE7/KUfWJ32TMzza1fv75Swe6K3LOjmjdvHs2bN6+y8wAAAACoHgXZLgAAAAAAAAAAAAAAdtZ+++0Xzz33XLRp0yY1t3Dhwhg7duw215cNVpeUlFT6zrJ7thXWrl27dhQWFu7UXRW5BwAAAID8JhQOAAAAAAAAAAAAQF5o2rRpjBkzJm3urrvu2ubask/HXrBgQaXvW7Ro0XbP3KJZs2Y7ddfChQsrdA8AAAAA+UsoHAAAAAAAAAAAAIC88a1vfSsSiURqvGjRopg3b95W6zp37pw2nj9/fqXuWbJkSaxfvz41Lioqio4dO25z7c7eVXb9AQccUKn9AAAAAOz+hMIBAAAAAAAAAAAAyBuNGjWKxo0bp80tXrx4q3Vlg9Vz5syJ0tLSCt8zY8aMtPG+++4bNWrU2ObasndNnz69wvds6y6hcAAAAIA9j1A4AAAAAAAAAAAAAHmtZs2aW83tvffesffee6fGX3zxRUyZMqXCZ7766qtp4x49emRcW/a9SZMmVfiejRs3xmuvvVbhuwAAAADIT0LhAAAAAAAAAAAAAOSN1atXx4oVK9LmWrRosc21xx9/fNr4ueeeq/A9Zdd+85vfzLi27D2TJk2KkpKSCt3z6quvxtq1a1Pj/fffP/bff/8K1wkAAABAfhAKBwAAAAAAAAAAACBvTJgwIZLJZGrcrFmz2Geffba59sQTT0wb33nnnWl7M5kzZ0689NJLqXHNmjXjuOOOy7i+TZs20bNnz9R4zZo18cADD5R7T0TE7bffnjY+6aSTKrQPAAAAgPwiFA4AAAAAAAAAAABAXli3bl1cdtllaXMnnHBCFBRs+5/MDhkyJFq3bp0az507N+68885y77n88svTwuOnnHJKNGzYcLt7hg8fnja+6qqrYv369dvdM2PGjPj73/+eGhcUFMQ555xTbn0AAAAA5B+hcAAAAAAAAAAAAAByysiRI+P111+v1J4VK1bEiSeeGB988EFqrrCwMC666KKMe2rVqhWXXnpp2twll1wS06dPz7jnvvvui7/+9a9pd4wZM6bc+n7wgx9E27ZtU+MPPvggLrroooxPJv/888/j7LPPjtLS0tTc6aefHl27di33LgAAAADyj1A4AAAAAAAAAAAAADnl2WefjUMOOSQOPfTQuO666+Ktt96KDRs2bLUumUzG+++/H1dccUV07tw5nn/++bT3L7roojjwwAO3e9fw4cOjW7duqfFnn30WRxxxRPzlL3+JjRs3puZXrFgRv/rVr+Kss85K23/eeefF/vvvX+5nKioqiquuuipt7k9/+lOceuqpMWvWrLT5F154IY444oh44403UnP16tWLX//61+XeAwAAAEB+qpHtAgAAAAAAAAAAAABgW1577bV47bXXIuLLUHWrVq2iUaNGUVRUFKtXr46PP/44Vq9evc293/3ud+Pqq68u946aNWvGgw8+GIcffnisWLEiIr4MgH/3u9+NH//4x7HvvvvGunXr4qOPPtoqmH7IIYfEtddeW+HPc9ppp8Urr7wSN998c2pu/Pjx8dBDD0WbNm2iWbNmMW/evFi2bFnavoKCgrjzzjujQ4cOFb4LAAAAgPwiFA4AAAAAAAAAAABAzistLY2PPvqo3HUNGjSIq666Ks4///xIJBIVOrtLly7xwgsvxEknnRTz5s1Lza9Zsybefvvtbe45+uij48EHH4zatWtX7AP8f3/4wx+iuLg4xo0bl5pLJpMxf/78mD9//lbr69SpE3feeWd8+9vfrtQ9AAAAAOSXgmwXAAAAAAAAAAAAAABfdf/998fVV18dRx99dDRo0KDc9YlEIrp37x5jx46N2bNnx49+9KMKB8K3OOigg+Ldd9+N0aNHx1577ZVxXadOneLWW2+NZ599Nho1alSpOyK+fOr3ddddFy+88EIcccQRGdcVFRXFGWecEdOmTYtTTz210vcAAAAAkF88KRwAAAAAAAAAAACAnNKlS5fo0qVLjBw5MjZv3hyzZs2K2bNnx/z58+Pzzz+PDRs2RP369aNhw4bRvn376NWrV4XC4+WpX79+/O53v4sxY8bE5MmTY9q0abF8+fIoLCyMffbZJ3r16hUHHnhgFXzCiIEDB8bAgQNjwYIFMWnSpJg/f36sX78+6tevH506dYrDDz+8Sj4TAAAAAPlBKBwAAAAAAAAAAACAnFVQUBCdO3eOzp0777I7a9asGYcffngcfvjh1X5X69atPQkcAAAAgHIVZLsAAAAAAAAAAAAAAAAAAAAAMhMKBwAAAAAAAAAAAAAAAAAAyGFC4QAAAAAAAAAAAAAAAAAAADlMKBwAAAAAAAAAAAAAAAAAACCHCYUDAAAAAAAAAAAAAAAAAADkMKFwAAAAAAAAAAAAAAAAAACAHCYUDgAAAAAAAAAAAAAAAAAAkMOEwgEAAAAAAAAAAAAAAAAAAHKYUDgAAAAAAAAAAAAAAAAAAEAOEwoHAAAAAAAAAAAAAAAAAADIYULhAAAAAAAAAAAAAAAAAAAAOUwoHAAAAAAAAAAAAAAAAAAAIIcJhQMAAAAAAAAAAAAAAAAAAOQwoXAAAAAAAAAAAAAAAAAAAIAcJhQOAAAAAAAAAAAAAAAAAACQw4TCAQAAAAAAAAAAAAAAAAAAcphQOAAAAAAAAAAAAAAAAAAAQA4TCgcAAAAAAAAAAAAAAAAAAMhhQuEAAAAAAAAAAAAAAAAAAAA5TCgcAAAAAAAAAAAAAAAAAAAghwmFAwAAAAAAAAAAAAAAAAAA5DChcAAAAAAAAAAAAAAAAAAAgBwmFA4AAAAAAAAAAAAAAAAAAJDDhMIBAAAAAAAAAAAAAAAAAABymFA4AAAAAAAAAAAAAAAAAABADhMKBwAAAAAAAAAAAAAAAAAAyGFC4QAAAAAAAAAAAAAAAAAAADlMKBwAAAAAAAAAAAAAAAAAACCHCYUDAAAAAAAAAAAAAAAAAADkMKFwAAAAAAAAAAAAAAAAAACAHCYUDgAAAAAAAAAAAAAAAAAAkMOEwgEAAAAAAAAAAAAAAAAAAHKYUDgAAAAAAAAAAAAAAAAAAEAOEwoHAAAAAAAAAAAAAAAAAADIYULhAAAAAAAAAAAAAAAAAAAAOUwoHAAAAAAAAAAAAAAAAAAAIIcJhQMAAAAAAAAAAAAAAAAAAOQwoXAAAAAAAAAAAAAAAAAAAIAcJhQOAAAAAAAAAAAAAAAAAACQw4TCAQAAAAAAAAAAAAAAAAAAcphQOAAAAAAAAAAAAAAAAAAAQA4TCgcAAAAAAAAAAAAAAAAAAMhhQuEAAAAAAAAAAAAAAAAAAAA5TCgcAAAAAAAAAAAAAAAAAAAghwmFAwAAAAAAAAAAAAAAAAAA5DChcAAAAAAAAAAAAAAAAAAAgBwmFA4AAAAAAAAAAAAAAAAAAJDDhMIBAAAAAAAAAAAAAAAAAAByWI1sFwAAAAAAAAAAAAAAAADklva/mFCl58296vgqPQ8AYE/jSeEAAAAAAAAAAAAAAAAAAAA5TCgcAAAAAAAAAAAAAAAAAAAghwmFAwAAAAAAAAAAAAAAAAAA5DChcAAAAAAAAAAAAAAAAAAAgBwmFA4AAAAAAAAAAAAAAAAAAJDDhMIBAAAAAAAAAAAAAAAAAABymFA4AAAAAAAAAAAAAAAAAABADhMKBwAAAAAAAAAAAAAAAAAAyGFC4QAAAAAAAAAAAAAAAAAAADlMKBwAAAAAAAAAAAAAAAAAACCHCYUDAAAAAAAAAAAAAAAAAADkMKFwAAAAAAAAAAAAAAAAAACAHCYUDgAAAAAAAAAAAAAAAAAAkMOEwgEAAAAAAAAAAAAAAAAAAHKYUDgAAAAAAAAAAAAAAAAAAEAOEwoHAAAAAAAAAAAAAAAAAADIYULhAAAAAAAAAAAAAAAAAAAAOUwoHAAAAAAAAAAAAAAAAAAAIIcJhQMAAAAAAAAAAAAAAAAAAOQwoXAAAAAAAAAAAAAAAAAAAIAcJhQOAAAAAAAAAAAAAAAAAACQw4TCAQAAAAAAAAAAAAAAAAAAcphQOAAAAAAAAAAAAAAAAAAAQA4TCgcAAAAAAAAAAAAAAAAAAMhhQuEAAAAAAAAAAAAAAAAAAAA5rEa2CwAAAAAAAAAAAAAAAADIpva/mFCl58296vgqPQ8AwJPCAQAAAAAAAAAAAAAAAAAAcphQOAAAAAAAAAAAAAAAAAAAQA4TCgcAAAAAAAAAAAAAAAAAAMhhQuEAAAAAAAAAAAAAAAAAAAA5TCgcAAAAAAAAAAAAAAAAAAAghwmFAwAAAAAAAAAAAAAAAAAA5DChcAAAAAAAAAAAAAAAAAAAgBwmFA4AAAAAAAAAAAAAAAAAAJDDhMIBAAAAAAAAAAAAAAAAAABymFA4AAAAAAAAAAAAAAAAAABADhMKBwAAAAAAAAAAAAAAAAAAyGFC4QAAAAAAAAAAAAAAAAAAADlMKBwAAAAAAAAAAAAAAAAAACCHCYUDAAAAAAAAAAAAAAAAAADkMKFwAAAAAAAAAAAAAAAAAACAHCYUDgAAAAAAAAAAAAAAAAAAkMOEwgEAAAAAAAAAAAAAAAAAAHKYUDgAAAAAAAAAAAAAAAAAAEAOEwoHAAAAAAAAAAAAAAAAAADIYULhAAAAAAAAAAAAAAAAAAAAOUwoHAAAAAAAAAAAAAAAAAAAIIcJhQMAAAAAAAAAAAAAAAAAAOQwoXAAAAAAAAAAAAAAAAAAAIAcJhQOAAAAAAAAAAAAAAAAAACQw4TCAQAAAAAAAAAAAAAAAAAAcphQOAAAAAAAAAAAAAAAAAAAQA4TCgcAAAAAAAAAAAAAAAAAAMhhQuEAAAAAAAAAAAAAAAAAAAA5TCgcAAAAAAAAAAAAAAAAAAAghwmFAwAAAAAAAAAAAAAAAAAA5DChcAAAAAAAAAAAAAAAAAAAgBwmFA4AAAAAAAAAAAAAAAAAAJDDhMIBAAAAAAAAAAAAAAAAAABymFA4AAAAAAAAAAAAAAAAAABADhMKBwAAAAAAAAAAAAAAAAAAyGFC4QAAAAAAAAAAAAAAAAAAADlMKBwAAAAAAAAAAAAAAAAAACCHCYUDAAAAAAAAAAAAAAAAAADkMKFwAAAAAAAAAAAAAAAAAACAHCYUDgAAAAAAAAAAAAAAAAAAkMOEwgEAAAAAAAAAAAAAAAAAAHKYUDgAAAAAAAAAAAAAAAAAAEAOEwoHAAAAAAAAAAAAAAAAAADIYULhAAAAAAAAAAAAAAAAAAAAOUwoHAAAAAAAAAAAAAAAAAAAIIcJhQMAAAAAAAAAAAAAAAAAAOQwoXAAAAAAAAAAAAAAAAAAAIAcJhQOAAAAAAAAAAAAAAAAAACQw4TCAQAAAAAAAAAAAAAAAAAAcphQOAAAAAAAAAAAAAAAAAAAQA4TCgcAAAAAAAAAAAAAAAAAAMhhQuEAAAAAAAAAAAAAAAAAAAA5TCgcAAAAAAAAAAAAAAAAgP/H3r1HaV2W+wO+ZxhmGME44wGUg6iIiOdYGwVBRVIMzDYoLgsQzdTdztgeUH8kU5RSlmape+OBNM2EQiywEATSpDzgiYAgGEblYIwclEFgBnh/f+zlu30H5vDC4HyF61rLtbyfee77fmYt/2Lx8QsAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAABAggmFAwAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAAAQIIJhQMAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAECCCYUDAAAAAAAAAAAAAAAAAAAkWF59PwAAAAAAgORauHBhzJ8/P9asWRM7duyIli1bRrdu3aJHjx6Rl1e/f8S8ffv2ePnll+Pvf/97rFu3Lho0aBCHHXZYnHrqqXH88cfXyY5Vq1bFggULoqSkJDZu3BgNGjSI5s2bR4cOHaJHjx5x8MEH18keAAAAAAAAAAAAqI5QOAAAAAAAGVKpVEycODHGjx8fS5cu3e2dli1bxjXXXBOjR4+Oxo0bf6bvKysrizvvvDMeeOCBWL9+/W7vHHvssXHzzTfH8OHDIycnp9azN2/eHNOmTYs//vGP8fzzz8fKlSurvNugQYM466yz4tvf/nYMHDgw698DAAAAAAAAAAAAaiu3vh8AAAAAAEBybNy4Mfr37x8jR46sMhAeEbFu3boYN25cdO/ePRYuXPiZvW/BggXRvXv3+MEPflBlIDwiYsmSJXHFFVfE+eefHx9++GGtZt9xxx1xyCGHxKWXXhqPPvpotYHwiIgdO3bE7NmzY9CgQXH++efH+++/n9XvAgAAAAAAAAAAALUlFA4AAAAAQEREbNmyJfr37x8zZ87MOM/Pz49jjjkmTjjhhF2+Cl5cXBx9+/aNZcuW7fP3LVmyJM4+++xYsWJFxnmTJk2ie/fucfTRR0fDhg0zfjZjxow4//zzY+vWrTXOnz9/fmzevHmX85ycnDjssMPipJNOipNPPjlatWq1y50//elPceaZZ8aaNWuy/K0AAAAAAAAAAACgZkLhAAAAAABERMSoUaPilVdeSde5ubkxZsyYeP/992PJkiXx9ttvx/r162PixInRvHnz9L3S0tIYMmRI7NixY5+9bfv27TF48OD44IMP0mctWrSIRx99NNavXx9vvfVWLF26NN5///247bbbIjf3//74+69//WvcdNNNWe0rLCyMr3/96/G73/0uSktLY/Xq1fHGG2/E66+/HmvXro1XX301Bg4cmNGzfPnyGDRoUOzcuXPvflkAAAAAAAAAAACoRCgcAAAAAID4xz/+EQ8++GDG2eOPPx7f+973MgLg+fn5MXz48HjxxRejWbNm6fM33ngjHnvssX32vkceeSQWLFiQrps3bx4vvvhifP3rX8/4OniLFi1i3Lhx8atf/Sqj/4EHHoh//vOfNe5p3bp1/OQnP4k1a9bEo48+GhdffHG0bNky405OTk6cdtpp8cwzz8S4ceMyfvbqq6/Go48+uie/IgAAAAAAAAAAAFRJKBwAAAAAgLj99tszvvT9ta99LYYOHVrl/eOPPz7uuuuujLOioqKoqKio87eVl5fvEr6+6667omvXrlX2XHbZZXH55Zen6+3bt8fYsWOr3XP11VdHcXFxjBo1Kpo2bVqrt912223xla98JePsoYceqlUvAAAAAAAAAAAA1JZQOAAAAADAAW7Dhg0xZcqUdJ2Tk1NjgDoiYsSIEdG+fft0/c4778SsWbPq/H0zZsyI9957L1136NAhRowYUWPf2LFjIycnJ11Pnjw5Pvzwwyrv9+vXL5o0aZL1+2655ZaM+m9/+1t89NFHWc8BAAAAAAAAAACAqgiFAwAAAAAc4KZPnx7bt29P13369IlOnTrV2Jebm7tLOHvq1Kl1/bx45plnMuoRI0ZkhL2rctRRR8VZZ52VrisqKuLZZ5+t8/eddtppUVhYmK537twZK1eurPM9AAAAAAAAAAAAHLiEwgEAAAAADnDTp0/PqM8777xa9/br1y+jnjZtWp286dOS/r6cnJxo2rRpxll1XyQHAAAAAAAAAACAbAmFAwAAAAAc4N58882MumfPnrXuPfXUU6OgoCBdr169OkpLS+vqafGvf/0r3n///XRdUFAQp5xySq37zzjjjIy68u9aFyoqKnb5nVu2bFnnewAAAAAAAAAAADhwCYUDAAAAABzAKioqYtmyZRlnXbt2rXV/QUFBHHXUURlnixcvrpO37W5W586dIz8/v9b9lX+XZcuWxfbt2+vkbZ+YN29e7NixI10XFBTEkUceWac7AAAAAAAAAAAAOLAJhQMAAAAAHMCKi4szQtKFhYXRqlWrrGYcccQRGfWSJUvq5G27m1V5V01at24djRo1Stfl5eWxYsWKOnnbJx555JGM+uyzz87YCQAAAAAAAAAAAHsrr74fAAAAAABA/Vm7dm1G3bZt26xnVO6pPHNvVJ7Vrl27rGccfvjhUVxcnDHz6KOP3uu3RUS8/fbb8cQTT2ScDR8+vE5mAwAAAABAh9HT63ReyZ0D6nQeAAAA8NkRCgcAAAAAOICVlZVl1I0bN856RuWeyjP3RpLft23bthg+fHjs2LEjfXbKKafEv//7v9fJ/E+sXbs2SktLs+pZtmxZnb4BAAAAAAAAAACA+iUUDgAAAABwAKsckG7UqFHWMwoLC6uduTeS/L7//M//jDfeeCNd5+XlxYMPPhi5ubl1Mv8T999/fxQVFdXpTAAAAAAAAAAAAD5f6vZvpgEAAAAA8LmydevWjDo/Pz/rGQUFBRn1li1b9upNn5bU9/385z+PCRMmZJyNGzcuTjnllL2eDQAAAAAAAAAAAJUJhQMAAAAA1KPrr78+cnJy9vk/Y8eO3e3+yl/eLi8vz/p32LZtW7Uz90YS3/f000/H9ddfn3F2ySWXxE033bRXcwEAAAAAAAAAAKAqefX9AAAAAAAA6k+TJk0y6spf5q6Nyl/erjxzbyTtfXPnzo2hQ4fGzp0702fnnXdePPbYY5GTk7PHc6tz7bXXxuDBg7PqWbZsWVx00UX75D0AAAAAAAAAAAB89oTCAQAAAAAOYJUD0ps3b856RuWefRkKr8/3vfbaazFw4MCML4//27/9W0yZMiXy8/P3aGZttGnTJtq0abPP5gMAAAAAAAAAAJB8QuEAAAAAAPVowIAB0apVq32+p3fv3rs9rxw2XrVqVdazK/fUZYC58qyVK1dmPWP16tXVzqyNhQsXxpe+9KXYtGlT+uzEE0+MZ599Nho3bpz1PAAAAAAAAAAAAMiGUDgAAAAAQD3q169f9OvXr972d+rUKfLy8mL79u0REbFly5YoLS2N1q1b13rGu+++m1F36dKlzt537LHHVrurJmvXro2tW7em6/z8/OjUqVNWM5YvXx79+vWLdevWpc+OOeaYeO6556JZs2ZZzQIAAAAAAAAAAIA9kVvfDwAAAAAAoP40bNgwjjrqqIyzRYsW1bp/27ZtUVxcnHFWl6HwyrOWL18e5eXlte5fvHhxRn3UUUdFXl7t/3+p7733XpxzzjmxZs2a9NmRRx4Zs2bNqtMvogMAAAAAAAAAAEB1hMIBAAAAAA5wJ510UkY9b968WvfOnz8/tm3blq4PO+ywOg1LH3rooXHooYem623btsX8+fNr3f/SSy9l1JV/1+qsXbs2zj333HjnnXcy3vP888/HEUccUes5AAAAAAAAAAAAsLeEwgEAAAAADnAXXnhhRj1z5sxa91a+++Uvf7lO3vRpAwYMqHZndfb0fRs2bIh+/frF0qVL02ctWrSImTNnRufOnWu9HwAAAAAAAAAAAOqCUDgAAAAAwAHuggsuiLy8vHQ9d+7cKC4urrEvlUrFL3/5y4yzQYMG1fXzYuDAgRn1xIkTI5VK1di3fPny+POf/5yuGzZsGBdccEGNfWVlZXH++efH22+/nT77whe+EDNmzIhu3bpl8XIAAAAAAAAAAACoG0LhAAAAAAAHuBYtWsRFF12UrlOpVIwdO7bGvkceeSRKSkrSdfv27ePcc8+t8/f1798/2rVrl65LSkpi4sSJNfaNHTs2Izz+1a9+NZo2bVptz9atW2PgwIHx8ssvp88KCwtj2rRpcdppp+3B6wEAAAAAAAAAAGDvCYUDAAAAABBFRUWRm/t/f2T8q1/9Kp588skq7y9atChuuOGGjLMxY8ZEfn5+tXtKSkoiJycn459PB8t3p6CgIG677baMsxtuuCEWLVpUZc+vf/3rePzxx9N1gwYNoqioqNo927dvj8GDB8ecOXPSZ/n5+fH0009Hr169qu0FAAAAAAAAAACAfSmvvh8AAAAAAED969q1a1x55ZUxYcKE9Nnll18eixcvju985zvRvHnziIioqKiIJ554IkaNGhUbN25M3+3evXsMGzZsn71v5MiR8Ytf/CIWLlwYEREbNmyIXr16xd133x2XXXZZ5OX97x93r1+/Pu6+++744Q9/mNF/9dVXxzHHHFPtjquuuiqmTZu2y1mDBg1i1qxZWb33+OOPj8MOOyyrHgAAAAAAAAAAAKiKUDgAAAAAABERcffdd8frr78er732WkRE7Ny5M77//e/H+PHjo2PHjlFQUBDFxcVRVlaW0deqVauYPHlyOpi9LzRs2DAmT54cZ555Zqxfvz4i/jcAPmzYsLjuuuviqKOOii1btsSKFSuioqIio/eLX/xi3HXXXTXu+PQXwj9x3333xX333Zf1eydOnBjDhw/Pug8AAAAAAAAAAAB2J7e+HwAAAAAAQDIcdNBBMWPGjDj77LMzzsvLy2PJkiXx9ttv7xII79ChQ8yePbvGr3DXheOOOy5mz54d7du3zzgvKyuLt956K5YuXbpLIPzcc8+NGTNmRGFh4T5/HwAAAAAAAAAAAOwrQuEAAAAAAKS1aNEiZs6cGRMmTIjOnTtXe+/WW2+NBQsWxAknnPCZve/EE0+MBQsWxC233BLNmzev8t7RRx8dDz74YDz33HPRrFmzz+x9AAAAAAAAAAAAsC/k1fcDAAAAAABIltzc3LjqqqviqquuigULFsTrr78ea9asiR07dkTLli2jW7du0aNHj2jYsGHWszt06BCpVGqv3nfwwQfHD3/4wygqKoqXX345/v73v8e6deuiQYMGcdhhh8Upp5yyR0H1kpKSvXoXAAAAAAAAAAAA7CtC4QAAAAAAVOmEE074TL8Eno2GDRvGmWeeGWeeeWZ9PwUAAAAAAAAAAAD2qdz6fgAAAAAAAAAAAAAAAAAAAABVEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABMur7wewf9q6dWvMmzcv/vGPf8SGDRsiPz8/2rVrFz169IhOnTrV6a7ly5fHK6+8EitXrozy8vJo3rx5dOnSJXr27BmNGjWq010AAAAAAAAAAAAAAAAAAPBZEwonhg4dGr/5zW8yztq3bx8lJSVZzyotLY2ioqL45S9/GZs3b97tnVNPPTXGjBkTgwYN2pPnpk2dOjW+//3vx+uvv77bnzdp0iSGDx8et99+e7Rq1WqvdgEAAAAAAAAAAAAAAAAAQH3Jre8HUL/+8Ic/7BII31Nz586Nrl27xn333VdlIDwiYv78+XHRRRfFsGHDory8POs927Zti8svvzy+8pWvVBkIj4goKyuLX/ziF9G1a9d44YUXst4DAAAAAAAAAAAAAAAAAABJIBR+APvwww/jmmuuqZNZf/nLX+KCCy6IDz74IOO8WbNmcfLJJ0eHDh2iQYMGGT977LHHYujQoZFKpWq9Z+fOnXHJJZfEE088kXHeoEGD6NixY5x00knRtGnTjJ+VlpbG+eefH3/961+z/K0AAAAAAAAAAAAAAAAAAKD+CYUfwG688cZYtWpVREQ0btx4j+ds2LAhLrnkktiyZUv6rH379jF16tRYv359vP7667FixYooKSmJq6++OqN3ypQpcffdd9d6149//ON45plnMs6++c1vxrvvvhvFxcXxxhtvxPr162PKlClx5JFHpu98/PHHMWTIkPjwww/38LcEAAAAAAAAAAAAAAAAAID6IRR+gJo7d2489NBDERGRm5sbt99++x7P+vGPfxyrV69O1x07dox58+bFoEGDIicnJ33erl27+O///u/4wQ9+kNH/ve99LzZs2FDjnnXr1u3Se8cdd8QDDzwQhx9+ePosNzc3vvKVr8S8efOiQ4cO6fOVK1fGT3/602x/PQAAAAAAAAAAAAAAAAAAqFdC4QegLVu2xJVXXhmpVCoiIr71rW/F6aefvkezSktL4+c//3nG2YMPPpgR0q7slltuid69e6frDz/8MO66664ad/3oRz+KTZs2pevevXvHzTffXOX9tm3bpoPvn7j77rtj3bp1Ne4CAAAAAAAAAAAAAAAAAICkEAo/AI0ZMyaWL18eERFHHnlkjBs3bo9n/eY3v4mysrJ03bt37zjnnHOq7cnJydnly+SPPPJIOqS+Ozt37oyJEydmnI0dOzbjS+S7c84550SvXr3S9aZNm2LSpEnV9gAAAAAAAAAAAAAAAAAAQJIIhR9gXn311bjnnnvS9X333RdNmjTZ43nPPPNMRj1y5Mha9fXt2zc6duyYrt9///3429/+VuX9efPmRWlpabru1KlT9OnTp1a7Kr9p6tSpteoDAAAAAAAAAAAAAAAAAIAkEAo/gFRUVMTIkSNjx44dERExePDguPDCC/d4XllZWbzwwgsZZ+edd16tenNycuLcc8/NOJs2bVqV96dPn55R9+vXr8avhH/67qfNnTs3Nm/eXKteAAAAAAAAAAAAAAAAAACob0LhB5A77rgjFixYEBERzZo1i3vvvXev5i1cuDAqKirSdceOHePQQw+tdf8ZZ5yRUb/55ptV3q38s549e9Z6z+GHHx4dOnRI1+Xl5bFo0aJa9wMAAAAAAAAAAAAAAAAAQH0SCj9ALFq0KH7wgx+k6/Hjx2cV4N6dxYsXZ9Rdu3bNqr/y/crz6msXAAAAAAAAAAAAAAAAAAAkiVD4AWDnzp0xcuTIKC8vj4iIXr16xVVXXbXXc5csWZJRH3HEEVn1V77/zjvvxNatW3e5t2XLlnj33XfrdFfltwMAAAAAAAAAAAAAAAAAQFIJhR8A7r333vjb3/4WERH5+fkxYcKEyMnJ2eu5a9euzajbtWuXVf8hhxwSeXl56Xrnzp2xbt26Xe598MEHkUql0nXDhg2jTZs2We1q27ZtRl357QAAAAAAAAAAAAAAAAAAkFR5NV/h82zFihXx//7f/0vXt9xyS3Tp0qVOZpeVlWXUjRs3zqo/JycnCgsLY9OmTVXO3N3ZQQcdlHWovfLbdrdnT61duzZKS0uz6lm2bFmd7QcAAAAAAAAAAAAAAAAAYP8mFL6f+8Y3vhGbN2+OiIguXbrErbfeWmezKwerGzVqlPWMPQmF7+me6mbujfvvvz+KiorqbB4AAAAAAAAAAAAAAAAAAHxabn0/gH3n4YcfjlmzZkXE/36Ve8KECZGfn19n87du3ZpR78nsgoKCjHrLli31tgcAAAAAAAAAAAAAAAAAAJJIKHw/tWbNmrjhhhvS9ZVXXhm9evWq0x2Vv9hdXl6e9Yxt27ZVO/Oz3AMAAAAAAAAAAAAAAAAAAEmUV98PYN+47rrrYuPGjRERceihh8aPfvSjOt/RpEmTjLryF71ro/IXuyvP/Cz37Klrr702Bg8enFXPsmXL4qKLLqqzNwAAAAAAAAAAAAAAAAAAsP8SCt8PTZ48OZ5++ul0/bOf/SyaNWtW53sqB6s3b96cVX8qldqjUPjHH38cqVQqcnJyar2r8tvqMhTepk2baNOmTZ3NAwAAAAAAAAAAAAAAAACAT8ut7wdQ92688cb0vw8YMCCGDBmyT/ZUDkKvXLkyq/5//etfsX379nSdm5sbrVq12uVeq1atMgLgFRUVsXbt2qx2rVq1KqMW4gYAAAAAAAAAAAAAAAAA4PNCKHw/tHHjxvS/T58+PXJycmr8p2/fvhkz3nnnnV3uvPnmmxl3jj322Iz63Xffzeqdle+3b98+GjVqtMu9wsLCOPLII+t0V5cuXbLqBwAAAAAAAAAAAAAAAACA+iIUzh6rHKxetGhRVv2LFy+udl597QIAAAAAAAAAAAAAAAAAgCQRCmePHX/88dGwYcN0XVJSEmvWrKl1/0svvZRRn3TSSVXerfyzefPm1XrPmjVroqSkJF03bNgwunbtWut+AAAAAAAAAAAAAAAAAACoT3n1/QDq3jPPPBMVFRVZ9bz11ltxww03pOtDDjkkHn/88Yw7nTt3zqgPPvjg6N27dzz//PPps5kzZ8bXv/71GvelUqmYNWtWxtmXv/zlKu9feOGFMX78+HQ9a9asSKVSkZOTU+Ou5557LqPu27dvNGnSpMY+AAAAAAAAAAAAAAAAAABIAqHw/dBZZ52VdU9eXuZ/Co0aNYpzzz23xr6BAwdmhMIffvjhWoXC58yZEytWrEjXhxxySPTo0aPK+z179oxWrVrFBx98EBERxcXFMXfu3Ojbt2+Nux5++OGMetCgQTX2AAAAAAAAAAAAAAAAAABAUuTW9wP4fLv00kujcePG6fqFF16I2bNnV9uTSqWiqKgo42zEiBGRm1v1f465ubkxfPjwjLOioqJIpVLV7nr++efjxRdfTNcHH3xwDBkypNoeAAAAAAAAAAAAAAAAAABIEqFw9kqbNm3iP/7jPzLOrrzyyli9enWVPXfccUe88MIL6bpp06Zx44031rjr5ptvjiZNmqTrP//5zzF+/Pgq769atSquvPLKjLNvf/vb0apVqxp3AQAAAAAAAAAAAAAAAABAUgiFs9duuummOPTQQ9P1ihUromfPnvH73/8+40veK1eujG9+85tx2223ZfTfdttt0aJFixr3tGrVKm699daMs1tuuSWuvfbajBD6zp07Y+rUqdGzZ88oKSlJnx9++OHxX//1X9n+egAAAAAAAAAAAAAAAAAAUK/y6vsBfP61aNEinnrqqejfv39s3bo1IiLeeeedGDRoUDRr1iw6duwYGzdujHfffTd27NiR0Tto0KC44YYbar3r5ptvjnnz5sW0adPSZw888EBMmDAh2rdvH02bNo0VK1bExo0bM/oKCwtj0qRJ0axZsz3+PQEAAAAAAAAAAAAAAAAAoD74Ujh1onfv3jF9+vRdvvi9cePGeOONN2LFihW7BMIvu+yyeOqppyInJ6fWe3Jzc2Py5Mlx6aWXZpzv2LEjiouL44033tglEN6yZct49tln44wzzsjulwIAAAAAAAAAAAAAAAAAgAQQCqfOnH322bFo0aK45ppr4qCDDqry3sknnxy/+93v4oknnoiCgoKs9zRq1CiefPLJ+O1vfxsnnXRSlfcaN24c1157bSxatCj69OmT9R4AAAAAAAAAAAAAAAAAAEiCvPp+AMnQp0+fSKVSez3nkEMOifvvvz9+8pOfxLx582Lx4sWxcePGyM/Pj7Zt20aPHj2ic+fOdfDiiK9+9avx1a9+NZYtWxYvv/xyrFq1KsrLy6NZs2Zx3HHHxRlnnBGNGjWqk10AAAAAAAAAAAAAAAAAAFBfhMLZJwoLC+Occ86Jc845Z5/v6ty5c50FzQEAAAAAAAAAAIDkSaVSUVJSEgsWLIiVK1fGxo0bo6CgIJo3bx5HH310nH766XX+IZlNmzbFSy+9FEuXLo2PPvooCgsLo3379tGzZ884/PDD63TXwoULY/78+bFmzZrYsWNHtGzZMrp16xY9evSIvDx/3RcAAAAAoXAAAAAAAAAAAAAAEmjDhg0xderU+NOf/hSzZ8+ODz74oMq7DRs2jAEDBsT1118fZ5111l7tXbFiRXz3u9+NSZMmRXl5+S4/z8nJibPOOiuKioqid+/ee7wnlUrFxIkTY/z48bF06dLd3mnZsmVcc801MXr06GjcuPEe7wIAAADg8y+3vh8AAAAAAAAAAAAAAJ923XXXxaGHHhpXXHFFTJo0qdpAeERERUVFTJ06Nfr06RPDhg2Ljz76aI/2Tpo0Kbp16xaPP/74bgPhEf8b5p47d2706dMnRo8eHalUKus9GzdujP79+8fIkSOrDIRHRKxbty7GjRsX3bt3j4ULF2a9BwAAAID9h1A4AAAAAAAAAAAAAIny8ssv7zaU3aBBg2jXrl2ceuqp0b1792jatOkudx577LHo169flJWVZbVz8uTJMXTo0Pj4448zzlu3bh2nnHJKtGvXLnJyctLnqVQqxo8fH6NGjcpqz5YtW6J///4xc+bMjPP8/Pw45phj4oQTTtjlq+DFxcXRt2/fWLZsWVa7AAAAANh/CIUDAAAAAAAAAAAAkFjNmjWLa6+9NqZPnx4bNmyI9957L1577bV46623Yt26dTFnzpzo1atXRs8rr7wSw4cPr/WO5cuXx4gRI2Lnzp3psxNPPDFmz54da9eujfnz58d7770Xixcvjosvvjij95577okpU6bUeteoUaPilVdeSde5ubkxZsyYeP/992PJkiXx9ttvx/r162PixInRvHnz9L3S0tIYMmRI7Nixo9a7AAAAANh/CIUDAAAAAAAAAAAAkDgdOnSIhx56KFavXh333XdfXHDBBXHwwQdn3GnQoEH06dMn5syZE9/4xjcyfva73/0u5syZU6tdY8aMic2bN6fr008/PV544YXo27dvxr1jjz02fvvb3+6y66abbort27fXuOcf//hHPPjggxlnjz/+eHzve9/LCIDn5+fH8OHD48UXX4xmzZqlz99444147LHHavU7AQAAALB/EQoHAAAAAAAAAAAAIFGKiopiyZIlMXLkyCgsLKzxfoMGDeL++++P0047LeP8oYceqrF34cKF8dRTT6Xr/Pz8ePTRR+MLX/jCbu/n5OTEz372szj66KPTZ8uXL4+JEyfWuOv222/P+NL31772tRg6dGiV948//vi46667Ms6KioqioqKixl0AAAAA7F+EwgEAAAAAAAAAAABIlAEDBkR+fn5WPQ0aNIibbrop42zGjBk19j3yyCOxc+fOdH3ppZfGcccdV21Po0aNYvTo0RlnNQXQN2zYEFOmTEnXOTk5MXbs2BrfN2LEiGjfvn26fuedd2LWrFk19gEAAACwfxEKBwAAAAAAAAAAAGC/0KtXr4x63bp18fHHH1fb8/vf/z6jHjlyZK12XXLJJdG4ceN0/eqrr8bq1aurvD99+vTYvn17uu7Tp0906tSpxj25ubkxYsSIjLOpU6fW6o0AAAAA7D+EwgEAAAAAAAAAAADYLzRv3nyXsw8//LDK+0uWLIlly5al68aNG0fPnj1rtavy3VQqFdOnT6/yfuWfnXfeebXaExHRr1+/jHratGm17gUAAABg/yAUDgAAAAAAAAAAAMB+YdWqVbuctWzZssr7b775Zkb9xS9+MfLy8mq974wzzqh2XnU/q234PCLi1FNPjYKCgnS9evXqKC0trXU/AAAAAJ9/QuEAAAAAAAAAAAAA7BdefPHFjLp9+/aRn59f5f3Fixdn1F27ds1qX+X7led9oqKiIuOL5NnuKigoiKOOOqpWuwAAAADYPwmFAwAAAAAAAAAAALBfeOSRRzLqCy64oNr7S5YsyaiPOOKIrPZVvl953ieKi4tj+/bt6bqwsDBatWq1T3YBAAAAsH/Kq+8HAAAAAAAAAAAAAMDeevbZZ+OFF17IOBs+fHi1PWvXrs2o27Vrl9XOtm3bZtSlpaW12lO5b092VZ65p9auXVvlu6tS+avnAAAAAOx7QuEAAAAAAAAAAAAAfK6tX78+rr766oyziy66KL74xS9W21dWVpZRN27cOKu9le9XVFTEtm3boqCgoE737K6n8sw9df/990dRUVGdzAIAAABg3xEKBwAAAAAAAAAAAOBza+fOnXH55ZfHypUr02dNmzaNe++9t8beysHqRo0aZbW7sLBwtzNrCoVnu2d3u+oqFA4AAFCdDqOn19mskjsH1NksgANRbn0/AAAAAAAAAAAAAAD21I033hh//OMfM87+53/+J4444ogae7du3ZpR5+fnZ7W7cvg7ImLLli11vmd3u3a3BwAAAID9ly+FAwAAAAAAAAAAAPC5dO+998ZPf/rTjLObbropLrnkklr1V/5id3l5eVb7t23bVuPMutizu1178rXx3bn22mtj8ODBWfUsW7YsLrroojrZDwAAAEDtCIUDAAAAAAAAAAAA8Lnz61//Oq6//vqMs+HDh8edd95Z6xlNmjTJqCt/0bsmu/tad+WZdbFnd7t2t2dPtGnTJtq0aVMnswAAAADYd3Lr+wEAAAAAAAAAAAAAkI1p06bFsGHDIpVKpc8uvvjieOihhyInJ6fWcyoHqzdv3pzVOyrfz8vL2+0XvPd2z+566ioUDgAAAMDng1A4AAAAAAAAAAAAAJ8bc+bMicGDB8f27dvTZ/369Ysnn3wyGjRokNWsyl/IXrlyZVb9q1atyqhbt25dqz2V+/Zkl697AwAAABxYhMIBAAAAAAAAAAAA+Fx4+eWXY+DAgbF169b0Wc+ePePpp5+O/Pz8rOcde+yxGfW7776bVX/l+126dNntvU6dOkVeXl663rJlS5SWlu6TXQAAAADsn4TCAQAAAAAAAAAAAEi8t99+O84///woKytLn5188snx7LPPRuPGjfdoZuVg9aJFi7LqX7x4cbXzPtGwYcM46qij9njXtm3bori4uFa7AAAAANg/CYUDAAAAAAAAAAAAkGhLliyJfv36xYYNG9Jnxx13XMyYMSOaNm26x3NPOumkjPrVV1+N7du317r/pZdeqnZedT+bN29erffMnz8/tm3blq4PO+ywaNOmTa37AQAAAPj8EwoHAAAAAAAAAAAAILHeeeedOPfcc2Pt2rXps44dO8bMmTOjdevWezW7S5cuGV/w3rx5c63D2ps3b46//vWv6TonJycuvPDCKu9X/tnMmTNr/c7Kd7/85S/XuhcAAACA/YNQOAAAAAAAAAAAAACJtGbNmjjnnHNi5cqV6bO2bdvG888/H23btq2THQMHDsyoH3744Vr1PfXUU1FWVpauTzvttDj88MOrvH/BBRdEXl5eup47d24UFxfXuCeVSsUvf/nLjLNBgwbV6o0AAAAA7D+EwgEAAAAAAAAAAABInPXr10e/fv1i+fLl6bPWrVvHzJkzo2PHjnW254orroicnJx0/Zvf/CYWL15cbc/WrVvjzjvvzDgbOXJktT0tWrSIiy66KF2nUqkYO3Zsje975JFHoqSkJF23b98+zj333Br7AAAAANi/CIUDAAAAAAAAAAAAkCibNm2KL33pS7Fw4cL0WbNmzeK5556L4447rk53devWLYYMGZKuy8vLY9iwYfHRRx/t9n4qlYrrr78+/vnPf6bPOnXqFFdccUWNu4qKiiI39//++u6vfvWrePLJJ6u8v2jRorjhhhsyzsaMGRP5+fk17gIAAABg/5JX3w8AAAAAAAAAAAAAgE8bOHBgvPrqqxlno0aNig8++CBmzZqV1axTTz01mjdvXu2dcePGxR/+8If4+OOPIyLi1Vdfjd69e8c999wTffr0Sd9bunRp3HLLLTFlypSM/jvvvDMaNmxY41u6du0aV155ZUyYMCF9dvnll8fixYvjO9/5TvqdFRUV8cQTT8SoUaNi48aN6bvdu3ePYcOG1bgHAAAAgP2PUDgAAAAAAAAAAAAAiTJ37txdzr773e/u0aw5c+ZkBLt3p3PnzvHwww/HZZddFqlUKiIi3nrrrejbt2+0bt06jjzyyFi7dm2sXLky/fNPfOtb34rBgwfX+j133313vP766/Haa69FRMTOnTvj+9//fowfPz46duwYBQUFUVxcHGVlZRl9rVq1ismTJ0denr/+CwAAAHAg8qdCAAAAAAAAAAAAABzwLr300kilUjFy5MjYsmVL+ry0tDRKS0t323PDDTfEj370o6z2HHTQQTFjxowYPHhwzJ49O31eXl4eS5Ys2W1Phw4d4ve//30cc8wxWe0CAAAAYP+RW98PAAAAAAAAAAAAAIAkGDp0aPz973+Pyy67LBo2bFjlvd69e8fcuXPjxz/+ceTk5GS9p0WLFjFz5syYMGFCdO7cudp7t956ayxYsCBOOOGErPcAAAAAsP/wpXAAAAAAAAAAAAAAEiWVStXb7k6dOsUTTzwRDzzwQPzlL3+Jf/7zn7Fp06Zo1KhRHHnkkXHGGWdE27Zt93pPbm5uXHXVVXHVVVfFggUL4vXXX481a9bEjh07omXLltGtW7fo0aNHteF0AAAAAA4cQuEAAAAAAAAAAAAAUMkXvvCFuOCCCz6TXSeccIIvgQMAAABQrdz6fgAAAAAAAAAAAAAAAAAAAABVEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASDChcAAAAAAAAAAAAAAAAAAAgAQTCgcAAAAAAAAAAAAAAAAAAEgwoXAAAAAAAAAAAAAAAAAAAIAEEwoHAAAAAAAAAAAAAAAAAABIMKFwAAAAAAAAAAAAAAAAAACABBMKBwAAAAAAAAAAAAAAAAAASLC8+n4AAAAAAAAAAAAAAAAAALvXYfT0Op1XcueAOp0HAHw2fCkcAAAAAAAAAAAAAAAAAAAgwYTCAQAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMGEwgEAAAAAAAAAAAAAAAAAABJMKBwAAAAAAAAAAAAAAAAAACDB8ur7AQAAAAAAAAAAAAAAAHCg6TB6ep3OK7lzQJ3OAwAgWXwpHAAAAAAAAAAAAAAAAAAAIMGEwgEAAAAAAAAAAAAAAAAAABJMKBwAAAAAAAAAAAAAAAAAACDBhMIBAAAAAAAAAAAAAAAAAAASTCgcAAAAAAAAAAAAAAAAAAAgwYTCAQAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMGEwgEAAAAAAAAAAAAAAAAAABJMKBwAAAAAAAAAAAAAAAAAACDBhMIBAAAAAAAAAAAAAAAAAAASLK++HwAAAAAAAAAAAAAAAAAAQNU6jJ5ep/NK7hxQp/OAfc+XwgEAAAAAAAAAAAAAAAAAABJMKBwAAAAAAAAAAAAAAAAAACDBhMIBAAAAAAAAAAAAAAAAAAASTCgcAAAAAAAAAAAAAAAAAAAgwYTCAQAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMGEwgEAAAAAAAAAAAAAAAAAABJMKBwAAAAAAAAAAAAAAAAAACDBhMIBAAAAAAAAAAAAAAAAAAASTCgcAAAAAAAAAAAAAAAAAAAgwYTCAQAAAAAAAAAAAAAAAAAAEiyvvh8AAAAAAAAAAAAAAAAAAAeiDqOn1+m8kjsH1Ok8AJLDl8IBAAAAAAAAAAAAAAAAAAASTCgcAAAAAAAAAAAAAAAAAAAgwYTCAQAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMGEwgEAAAAAAAAAAAAAAAAAABJMKBwAAAAAAAAAAAAAAAAAACDBhMIBAAAAAAAAAAAAAAAAAAASTCgcAAAAAAAAAAAAAAAAAAAgwYTCAQAAAAAAAAAAAAAAAAAAEkwoHAAAAAAAAAAAAAAAAAAAIMHy6vsBAAAAAAAAAAAAAAAAAADZ6DB6ep3OK7lzQJ3OA6hrvhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGBC4QAAAAAAAAAAAAAAAAAAAAkmFA4AAAAAAAAAAAAAAAAAAJBgQuEAAAAAAAAAAAAAAAAAAAAJJhQOAAAAAAAAAAAAAAAAAACQYELhAAAAAAAAAAAAAAAAAAAACSYUDgAAAAAAAAAAAAAAAAAAkGB59f0APhupVCpKSkpiwYIFsXLlyti4cWMUFBRE8+bN4+ijj47TTz89GjVqVKc7N23aFC+99FIsXbo0PvrooygsLIz27dtHz5494/DDD6/TXQsXLoz58+fHmjVrYseOHdGyZcvo1q1b9OjRI/Ly/GcOAAAAAAAAAAAAAAAAAMDnl7TsfmzDhg0xderU+NOf/hSzZ8+ODz74oMq7DRs2jAEDBsT1118fZ5111l7tXbFiRXz3u9+NSZMmRXl5+S4/z8nJibPOOiuKioqid+/ee7wnlUrFxIkTY/z48bF06dLd3mnZsmVcc801MXr06GjcuPEe7wIAAAAAAAAAAAAAAAAAgPqSW98PYN+47rrr4tBDD40rrrgiJk2aVG0gPCKioqIipk6dGn369Ilhw4bFRx99tEd7J02aFN26dYvHH398t4HwiP8Nc8+dOzf69OkTo0ePjlQqlfWejRs3Rv/+/WPkyJFVBsIjItatWxfjxo2L7t27x8KFC7PeAwAAAAAAAAAAAAAAAAAA9U0ofD/18ssv7zaU3aBBg2jXrl2ceuqp0b1792jatOkudx577LHo169flJWVZbVz8uTJMXTo0Pj4448zzlu3bh2nnHJKtGvXLnJyctLnqVQqxo8fH6NGjcpqz5YtW6J///4xc+bMjPP8/Pw45phj4oQTTtjlq+DFxcXRt2/fWLZsWVa7AAAAAAAAAAAAAAAAAACgvgmFHwCaNWsW1157bUyfPj02bNgQ7733Xrz22mvx1ltvxbp162LOnDnRq1evjJ5XXnklhg8fXusdy5cvjxEjRsTOnTvTZyeeeGLMnj071q5dG/Pnz4/33nsvFi9eHBdffHFG7z333BNTpkyp9a5Ro0bFK6+8kq5zc3NjzJgx8f7778eSJUvi7bffjvXr18fEiROjefPm6XulpaUxZMiQ2LFjR613AQAAAAAAAADw/9m78zityrp/4F+GGRYB2VEBYQBNwA0lNSEVFzRxQSvcHktx+ZnW82RlrhFiVJimPT2luW/1lGmKPlI/xBQ3Cs1dIQwBEVwYVgFhhuX8/vDX/XQPs93DPTNn5n6/Xy9fr64z57qu7z2da87M4XzOAQAAAAAAoKkJhbdgpaWlcfvtt8f7778fv/zlL2PMmDHRqVOnrH1at24do0aNiqeeeir+z//5P1lf+8Mf/hBPPfVUneaaMGFCrF+/PtM+4IAD4plnnonDDz88a7899tgjHnzwwW3muvTSS2Pz5s21zvP3v/89brvttqxtv/71r+Oaa67JCoC3adMmzj777Hj22WejS5cume2vvPJK3HvvvXX6TAAAAAAAAAAAAAAAAAAAkAZC4S3UpEmTYt68eXHuuedG+/bta92/devWcdNNN8VnP/vZrO233357rX3feuutuP/++zPtNm3axD333BM77rhjlfu3atUq/vM//zN23333zLZ33nkn7rrrrlrnmjhxYtabvr/yla/E6aefXu3+e+65Z1x//fVZ2yZNmhSbNm2qdS4AAAAAAAAAAAAAAAAAAEgDofAW6rjjjos2bdrk1Kd169Zx6aWXZm2bPn16rf3uvPPO2Lp1a6Z92mmnxZAhQ2rs065du7j88suzttUWQF+1alU89NBDmXarVq3i6quvrrW+8ePHR//+/TPtd999N5544ola+wEAAAAAAAAAAAAAAAAAQBoIhZPlkEMOyWqvWLEiPvnkkxr7PProo1ntc889t05znXrqqdGhQ4dM+8UXX4z333+/2v2nTZsWmzdvzrRHjRoVAwcOrHWeoqKiGD9+fNa2qVOn1qlGAAAAAAAAAAAAAAAAAABoakLhZOnates229asWVPt/vPmzYv58+dn2h06dIgRI0bUaa7K+yZJEtOmTat2/8pfO/roo+s0T0TE6NGjs9qPPfZYnfsCAAAAAAAAAAAAAAAAAEBTEgony9KlS7fZ1r1792r3f/XVV7PaBx54YBQXF9d5vpEjR9Y4Xk1fq2v4PCJi+PDh0bZt20z7/fffj7Kysjr3BwAAAAAAAAAAAAAAAACApiIUTpZnn302q92/f/9o06ZNtfvPnTs3qz106NCc5qu8f+Xx/mnTpk1ZbyTPda62bdvGoEGD6jQXAAAAAAAAAAAAAAAAAACkiVA4We68886s9pgxY2rcf968eVntXXfdNaf5Ku9febx/WrBgQWzevDnTbt++ffTo0aNB5gIAAAAAAAAAAAAAAAAAgDQpbuoCSI8//vGP8cwzz2RtO/vss2vss2zZsqx23759c5qzT58+We2ysrI6zVO5X33mqjxmfS1btqzauqtT+a3nAAAAAAAAAAAAAAAAAABQHaFwIiJi5cqVccEFF2RtO+mkk+LAAw+ssd+6deuy2h06dMhp3sr7b9q0KcrLy6Nt27Z5naeqPpXHrK+bbropJk2alJexAAAAAAAAAAAAAAAAAACgsqKmLoCmt3Xr1jjzzDNjyZIlmW2dO3eOn//857X2rRysbteuXU5zt2/fvtYx8zFPVXPlKxQOAAAAAAAAAAAAAAAAAAANyZvCie9+97vxpz/9KWvbLbfcErvuumutfTdu3JjVbtOmTU5zV34jeETEhg0b8j5PVXNVNQ8AAAAAAAAAAABAxKf3Ls6aNSv+/ve/x6pVq6JNmzbRt2/fOOigg2LgwIF5neudd96JF154IZYsWRIVFRXRtWvXGDx4cIwYMaJeL9IBAAAAoOURCi9wP//5z+OGG27I2nbppZfGqaeeWqf+lS80VlRU5DR/eXl5rWPmY56q5srXRdKLLrooxo0bl1Of+fPnx0knnZSX+QEAAAAAAAAAAKAQLF26NF544YWYPXt2vPDCC/G3v/0t1q5dm/l6//79Y9GiRds9T1lZWUyaNCnuvvvuWL9+fZX7DB8+PCZMmBBjx47drrmmTp0aP/jBD+Lll1+u8usdO3aMs88+OyZOnBg9evTYrrkAAAAAaN6EwgvYf//3f8fFF1+cte3ss8+OKVOm1HmMjh07ZrUrv9G7NlW9rbvymPmYp6q5qpqnPnr16hW9evXKy1gAAAAAAAAAAADA/3r++efjpz/9acyePTvef//9Bp9v5syZMW7cuFi+fHmN+7300ktx0kknxVe/+tW47bbbok2bNjnNU15eHueee2785je/qXG/devWxS9+8Yu4//7748EHH4xDDz00p3kAAAAAaDmKmroAmsZjjz0WZ511ViRJktn2xS9+MW6//fZo1apVncepHKyu7omY1am8f3FxcZVv8N7eearqk69QOAAAAAAAAAAAANAwXnzxxXj44YcbJRD+3HPPxZgxY7YJhHfp0iX222+/KC0tjdatW2d97d57743TTz89637M2mzdujVOPfXUbQLhrVu3jgEDBsSwYcOic+fOWV8rKyuLY489Nv7yl7/k+KkAAAAAaCmEwgvQU089FePGjYvNmzdnto0ePTp++9vfbnOxsjaV35C9ZMmSnPovXbo0q92zZ886zVO5X33m8nZvAAAAAAAAAAAAaL7y+XKYVatWxamnnhobNmzIbOvfv39MnTo1Vq5cGS+//HIsXLgwFi1aFBdccEFW34ceeihuvPHGOs913XXXxSOPPJK17Wtf+1osXrw4FixYEK+88kqsXLkyHnrooejXr19mn08++SROOeWUWLNmTT0/JQAAAADNmVB4gZk9e3aceOKJsXHjxsy2ESNGxMMPPxxt2rTJebw99tgjq7148eKc+lfef/DgwVXuN3DgwCguLs60N2zYEGVlZQ0yFwAAAAAAAAAAAJAunTp1ilGjRsV3v/vdeOCBB2LRokXxP//zP3kb/7rrrst6G/mAAQNi1qxZMXbs2GjVqlVme9++feNXv/pV/PCHP8zqf80118SqVatqnWfFihXb9P3xj38cN998c/Tu3TuzraioKE4++eSYNWtWlJaWZrYvWbIkbrjhhlw/HgAAAAAtQHHtu9BSvP7663HsscfGunXrMtv222+/+OMf/xgdOnSo15iVg9Vz5szJqf/cuXNrHO+fSkpKYtCgQTFv3rysuQ477LA6zVNeXh4LFiyo01wAAAAAwKfeeuuteOmll+KDDz6ILVu2RPfu3WOvvfaKgw46KOshjk1h8+bNMXv27HjzzTdjxYoV0bp169hll11i+PDhseeeezZpbQAAAABA/pxwwglx9NFHx+DBg6OoKPtdSAsXLszLHGVlZfFf//VfWdtuu+22rJB2ZVdccUVMnz49nnnmmYiIWLNmTVx//fXbBL4r+8lPfhJr167NtA899NC47LLLqt2/T58+cfvtt8dRRx2V2XbjjTfGf/zHf0T37t1rnAsAAACAlkUovEDMmzcvRo8enfUUyiFDhsT06dOjc+fO9R532LBhWe0XX3wxNm/eXOcbQp9//vkax6v8tX8Nhc+aNavOofCXXnopysvLM+1ddtklevXqVae+AAAAAFBIkiSJu+66K6699tp4++23q9yne/fuceGFF8bll19e7wdO1te6detiypQpcfPNN8fKlSur3GePPfaIyy67LM4+++ysN/jkyxVXXBFTpkzZZnuSJHmfCwAAAAAK3aBBgxp8jt/97ndZL9w59NBD48gjj6yxT6tWrWLixIlZ+915550xefLkaq9Lbt26Ne42r5UIAACFtElEQVS6666sbVdffXWt1zGPPPLIOOSQQ+LZZ5+NiIi1a9fG73//+7jwwgtr7AcAAABAy1JU+y40d++++24cddRRsWzZssy2AQMGxIwZM6Jnz57bNfbgwYOzLriuX78+Zs2aVae+69evj7/85S+ZdqtWreL444+vdv/KX5sxY0ad66y87wknnFDnvgAAAABQKFavXh3HHHNMnHvuudUGwiMiVqxYEZMnT4599tkn3nrrrUar74033oh99tknfvjDH1YbCI/49CGZ55xzThx77LGxZs2avNbwyiuvxPXXX5/XMQEAAACApvXII49ktc8999w69Tv88MNjwIABmfaHH34Yf/3rX6vdf9asWVFWVpZpDxw4MEaNGlWnuSrXNHXq1Dr1AwAAAKDlEApv4T744IM48sgjY8mSJZltffr0iT//+c/Rp0+fvMxx4oknZrXvuOOOOvW7//77s56s+dnPfjZ69+5d7f5jxozJegP5zJkzY8GCBbXOkyRJ3H333Vnbxo4dW6caAQAAAKBQbNiwIY455phtHrDYpk2b+MxnPhN77733Nm8FX7BgQRx++OExf/78Bq9v3rx5ccQRR8TChQuztnfs2DH22Wef2H333aOkpCTra9OnT49jjz02Nm7cmJcaNm/eHOecc05s3rw5L+MBAAAAAE1v3bp18cwzz2RtO/roo+vUt1WrVnHUUUdlbXvssceq3X/atGlZ7dGjR9f6lvB/3fdfzZw5M9avX1+nvgAAAAC0DELhLdjKlStj9OjR8c4772S29ezZM2bMmJH1ZMrtdc4552RdlPzd734Xc+fOrbHPxo0bY8qUKVnbanuyZrdu3eKkk07KtJMkiauvvrrW+u68885YtGhRpt2/f/9tLsICAAAAQKH79re/HS+88EKmXVRUFBMmTIgPP/ww5s2bF6+//nqsXLky7rrrrujatWtmv7KysjjllFNiy5YtDVbb5s2bY9y4cbF8+fLMtm7dusU999wTK1eujNdeey3efvvt+PDDD+Oqq66KoqL/vfT9l7/8JS699NK81PGTn/wkXn311YiIbQLyAAAAAEDz9NZbb8WmTZsy7QEDBsTOO+9c5/4jR47Mav/zGmJVKn9txIgRdZ6nd+/eUVpammlXVFTEnDlz6twfAAAAgOZPKLyFWrt2bXzhC1+It956K7OtS5cu8fjjj8eQIUPyOtdee+0Vp5xySqZdUVERZ511Vnz88cdV7p8kSVx88cXxj3/8I7Nt4MCBcc4559Q616RJk7Ju6Lzvvvvit7/9bbX7z5kzJy655JKsbRMmTIg2bdrUOhcAAAAAFIq///3vcdttt2Vt+/Wvfx3XXHNNVgC8TZs2cfbZZ8ezzz4bXbp0yWx/5ZVX4t57722w+u6888544403Mu2uXbvGs88+G1/96lez3g7erVu3mDx5ctx3331Z/W+++eas65H1MW/evLjmmmsy7X/93wAAAABA81X5JThDhw7NqX/l/Wt6qU5jzgUAAABAyyMU3kKdeOKJ8eKLL2Zt+/a3vx3Lly+PJ554Iqf/Vq1aVet8kydPjh122CHTfvHFF+PQQw+NmTNnZu339ttvx5e//OW45ZZbsrZPmTIl6+bN6gwdOjTOO++8rG1nnnlmfP/738+qc9OmTXH33XfH5z//+Vi9enVm+z777BNnnXVWrfMAAAAAQCGZOHFi1pu+v/KVr8Tpp59e7f577rlnXH/99VnbJk2alPU2nXypqKiIyZMnZ227/vrra7xZ8owzzogzzzwz0968eXNcffXV9a4hSZI477zzory8PCIixo4dG1/84hfrPR4AAAAAkB7z5s3Lau+666459a+8/7vvvhsbN27cZr8NGzbE4sWL8zpX5doBAAAAaNmKm7oAGkblMHZExPe///16jfXUU0/FqFGjatxnt912izvuuCPOOOOMSJIkIiJee+21OPzww6Nnz57Rr1+/WLZsWSxZsiTz9X/693//9xg3blyd67nxxhvj5Zdfjr/97W8REbF169b4wQ9+ENdee20MGDAg2rZtGwsWLIh169Zl9evRo0c88MADUVzssAcAAACAf1q1alU89NBDmXarVq3qFKAeP358/OAHP4h33303Ij690fGJJ56IY489Nq/1TZ8+Pd57771Mu7S0NMaPH19rv6uvvjp+85vfZK5HPvDAA3HTTTdF586dc67hl7/8ZTz33HMREdGpU6f4xS9+EZs3b855HAAAAAAgfZYtW5bV7tu3b079d9pppyguLs5cM9y6dWusWLEi+vTpk7Xf8uXLs+6fLCkpiV69euU0V+UxK9deX8uWLYuysrKc+syfPz8vcwMAAABQd9Kx5M1pp50WSZLEueeeGxs2bMhsLysrq/Zi4SWXXBI/+clPcppnhx12iOnTp8e4cePiySefzGyvqKio9qmXpaWl8eijj8ZnPvOZnOYCAAAAgJZu2rRpWQHnUaNGxcCBA2vtV1RUFOPHj88KkE+dOjXvofBHHnkkqz1+/Pho1apVrf0GDRoUhx12WOYBmps2bYo//vGPNb4BvSqLFy+OK664ItP+0Y9+FH379o1FixblNA4AAAAAkE6VX0DToUOHnPq3atUq2rdvH2vXrq12zKq27bDDDnW61llTbVXNUx833XRTTJo0KS9jAQAAANBwipq6AFqW008/Pd58880444wzoqSkpNr9Dj300Jg5c2Zcd911OV/UjIjo1q1bzJgxI2699dbYbbfdatzvyiuvjDfeeCP23nvvnOcBAAAAgJZu2rRpWe2jjz66zn1Hjx6d1X7sscfyUtO/aur6LrjggsyNlZ/73OfioosuynkMAAAAACC9Kger27Vrl/MY7du3r3HMxpwHAAAAgJbLm8JbqCRJmmzugQMHxm9+85u4+eab47nnnot//OMfsXbt2mjXrl3069cvRo4cGX369NnueYqKiuL888+P888/P9544414+eWX44MPPogtW7ZE9+7dY6+99oqDDjqoxnA6AAAAABS6V199Nas9YsSIOvcdPnx4tG3bNsrLyyMi4v3334+ysrLo2bNnXmr76KOP4sMPP8y027ZtG/vvv3+d+48cOTKrXfmz1ubee++N//t//29ERJSUlMStt94aRUWetQoAAAAALcnGjRuz2m3atMl5jLZt22a1N2zY0GTzAAAAANByCYXTYHbccccYM2ZMo8y19957exM4AAAAAORo06ZNMX/+/KxtQ4cOrXP/tm3bxqBBg2LOnDmZbXPnzs1bKHzu3LlZ7d122y2nGyUrf5b58+fH5s2bo7i49kvjy5Yti29961uZ9iWXXOIaJAAAAAC0QJXf2F1RUZHzGP98cGZ1YzbmPPVx0UUXxbhx43LqM3/+/DjppJPyMj8AAAAAdSMUDgAAAABQoBYsWBCbN2/OtNu3bx89evTIaYxdd901KxQ+b968OPTQQ/NS37x587aZKxc9e/aMdu3aZd7AU1FREQsXLozdd9+91r7f+MY3YuXKlRHxaRj9+9//fk5zAwAAAADNQ8eOHbPald/oXReV39hdeczGnKc+evXqFb169crLWAAAAAA0nKKmLgAAAAAAgKaxbNmyrHafPn1yHqNyn8pjbo/KY/Xt2zfnMXr37l3jmFV55JFH4oEHHsi0b7nllry9cQcAAAAASJfKwer169fn1D9JknqFwj/55JNIkiSnuSrXlq9QOAAAAADNgzeFAwAAAAAUqHXr1mW1O3TokPMYlftUHnN7NEV9a9asiYsuuijTPuuss+KII47Ied58WrZsWZSVleXUZ/78+Q1UDQAAAAC0LJXfkL1kyZKc+n/00UexefPmTLuoqCh69OixzX49evSIVq1aZYLgmzZtimXLlsVOO+1U57mWLl2a1fZ2bwAAAIDCIhQOAAAAAFCgKgek6/M27Pbt29c45vZoivq+853vxPvvvx8RET179oyf/vSnOc+ZbzfddFNMmjSpqcsAAAAAgBZpjz32yGovXrw4p/6V9+/fv3+V1zLbt28f/fr1i3fffTerby6h8MpzDR48OKdaAQAAAGjeipq6AAAAAAAAmsbGjRuz2m3atMl5jLZt22a1N2zYsF01/avGru/Pf/5z3HHHHZn2DTfcEN27d895TgAAAACg+agcrJ4zZ05O/efOnVvjeE01FwAAAAAtj1A4AAAAAEATufjii6NVq1YN/t/VV19d5fyV31ZTUVGR82coLy+vcczt0Zj1ffLJJ3H++edn2kcffXSceeaZOc8HAAAAADQve+65Z5SUlGTaixYtig8++KDO/Z9//vms9rBhw6rdt/LXZs2aVed5Pvjgg1i0aFGmXVJSEkOHDq1zfwAAAACav+KmLgAAAAAAgKbRsWPHrHblN3PXReU3b1cec3s0Zn1XXXVVLFy4MCIidthhh7j55ptznquhXHTRRTFu3Lic+syfPz9OOumkhikIAAAAAFqQTp06xaGHHhp//vOfM9tmzJgRX/3qV2vtmyRJPPHEE1nbTjjhhGr3P/744+Paa6/NtJ944olIkiRatWpV61yPP/54Vvvwww/P6/VYAAAAANJPKBwAAAAAoEBVvmFw/fr1OY9RuU9DhsIbqr7Zs2fHz3/+80x74sSJMXDgwJznaii9evWKXr16NXUZAAAAANBinXjiiVmh8DvuuKNOofCnnnoq87DJiIiddtopDjrooGr3HzFiRPTo0SOWL18eERELFiyImTNnxuGHH17rXHfccUdWe+zYsbX2AQAAAKBlEQoHAAAAAGgixx13XPTo0aPB5zn00EOr3F45aLx06dKcx67cJ5/h5cpjLVmyJOcx3n///RrHjIi47LLLYuvWrRERse+++8a3v/3tnOcBAAAAAJqv0047La688srMQyafeeaZePLJJ+OII46otk+SJDFp0qSsbePHj4+ioqJq+xQVFcXZZ58d119/fWbbpEmTYtSoUTW+LfzPf/5zPPvss5l2p06d4pRTTqn1cwEAAADQsgiFAwAAAAA0kdGjR8fo0aObbP6BAwdGcXFxbN68OSIiNmzYEGVlZdGzZ886j7F48eKs9uDBg/NW3x577FHjXLVZtmxZbNy4MdNu06ZNlW8AX716deZ/v/baa1FSUpJbof9f5Zs2H3744TjppJPqNRYAAAAA0Hh69eoV3/jGN+Laa6/NbDvvvPPiueeei969e1fZ58c//nE888wzmXbnzp3ju9/9bq1zXXbZZfGrX/0q1q1bFxERTz/9dFx77bVx+eWXV7n/0qVL47zzzsva9s1vfrNRHjgKAAAAQLoIhQMAAAAAFKiSkpIYNGhQzJs3L7Ntzpw5cdhhh9Wpf3l5eSxYsCBrWz5D4ZXHeuedd6KioiLatGlTp/5z587Nag8aNCiKi10WBwAAAIDm5vnnn48NGzZss/21117Lam/cuDGeeOKJKsfo3bt3DB06tNo5Lr300rjnnnviww8/jIiIhQsXxogRI+LnP/95nHDCCZmHQi5ZsiQmT54ct9xyS1b/q666Krp161brZ+nRo0dceeWVceWVV2a2XXHFFbF48eL43ve+lwmhb926NR599NH45je/mfXAzN69e8d3vvOdWucBAAAAoOVx9xsAAAAAQAEbNmxYVih81qxZdQ6Fv/TSS1FeXp5p77LLLtGrV6+81bbzzjvHzjvvnLkJs7y8PF566aU4+OCD69T/+eefz2oPGzYsb7UBAAAAAI3n3/7t3+Ldd9+tdb+PPvooRo8eXeXXzjrrrLj77rur7dutW7e4//7745hjjomNGzdGRMS7774bY8eOjS5dusSAAQNi9erVsXjx4tiyZUtW37Fjx8Yll1xS589z2WWXxaxZs+Kxxx7LbLv55pvj1ltvjf79+0fnzp1j4cKFsXr16qx+7du3j9///vfRpUuXOs8FAAAAQMshFA4AAAAAUMCOP/74uP/++zPtGTNmxBVXXFGnvjNmzMhqn3DCCXmtLSLiuOOOizvuuCNrzrqGwuta3y233BJr167Nqa6PPvoozjzzzBrn23fffXMaEwAAAABoWoceemhMmzYtxo0bFytXrsxsX716dbzyyitV9jnjjDPizjvvzLxJvC6KiorigQceiPHjx8fvfve7zPYtW7bEggULquzTvXv3ePDBB2PkyJF1ngcAAACAlkUoHAAAAACggI0ZMyaKi4tj8+bNERExc+bMWLBgQQwcOLDGfkmSbPNWnbFjx+a9vhNPPDErFH7XXXfFhAkTar3B8p133omnn3460y4pKYkxY8ZUue9BBx2Uc12LFi3aZttRRx2V8zgAAAAAQLocccQRMWfOnJg0aVLcc8898cknn1S533777Rff+9734otf/GK95mnXrl389re/jS9/+csxefLkePXVV6vcr0OHDnHWWWfFxIkTo1evXvWaCwAAAICWQSgcAAAAAKCAdevWLU466aR48MEHI+LTsPfVV18d9957b4397rzzzqxgdP/+/RskFH3MMcdE3759Y8mSJRHxaRj7rrvuinPOOafGfldffXUkSZJpf+lLX4rOnTvnvT4AAAAAoOFV9ZDGhrTTTjvFTTfdFD/96U9j1qxZMXfu3Fi9enW0adMm+vTpEwcddFDstttueZnrS1/6UnzpS1+K+fPnx+zZs2Pp0qVRUVERXbp0iSFDhsTIkSOjXbt2eZkLAAAAgOZNKBwAAAAAoMBNmjQpHnroodi6dWtERNx3331x7LHHxumnn17l/nPmzIlLLrkka9uECROiTZs2Nc6zaNGiGDBgQNa2hQsXRmlpabV92rZtG1dddVVceOGFmW2XXHJJfO5zn4uhQ4dW2ee///u/49e//nWm3bp165g0aVKNtQEAAAAAVNa+ffs48sgj48gjj2zwuXbbbbe8Bc0BAAAAaJmKmroAAAAAAACa1tChQ+O8887L2nbmmWfG97///Vi1alVm26ZNm+Luu++Oz3/+87F69erM9n322SfOOuusBqvv3HPPjT333DPTXrVqVRxyyCFx7733xubNmzPbV65cGRMmTIivfOUrWf0vuOCC+MxnPtNg9QEAAAAAAAAAAEBDEwoHAAAAACBuvPHG+OxnP5tpb926NX7wgx/EzjvvHIMHD4599903unXrFuPHj88Kivfo0SMeeOCBKC4ubrDaSkpK4oEHHohu3bpltq1cuTLOOuus6Nq1awwbNiz22GOP2HnnnWPy5MmZN55HRBx44IFx/fXXN1htAAAAAAAAAAAA0BiEwgEAAAAAiB122CGmT58eRxxxRNb2ioqKmDdvXrz++uuxbt26rK+VlpbGk08+2Shv4R4yZEg8+eST0b9//6zt69ati9deey3efvvt2LRpU9bXjjrqqJg+fXq0b9++wesDAAAAAAAAAACAhiQUDgAAAABARER069YtZsyYEbfeemvstttuNe535ZVXxhtvvBF77713o9W37777xhtvvBFXXHFFdO3atdr9dt9997jtttvi8ccfjy5dujRafQAAAAAAAAAAANBQipu6AAAAAAAA0qOoqCjOP//8OP/88+ONN96Il19+OT744IPYsmVLdO/ePfbaa6846KCDoqSkJOexS0tLI0mS7aqvU6dO8aMf/SgmTZoUs2fPjjfffDNWrFgRrVu3jl122SX233//Rgmq5+OzAAAAAAAAAAANr/TyaXkdb9GU4/I6HgDUlVA4AAAAAABV2nvvvRv1TeC5KCkpic9//vPx+c9/vqlLAQAAAAAAAAAAgAZX1NQFAAAAAAAAAAAAAAAAAAAAUD2hcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASLHipi4AAAAAAAAAAAAAAAAAgOap9PJpeR1v0ZTj8joeALQU3hQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKVbc1AUAAAAAAAAAAAAAAAAAANB8lV4+La/jLZpyXF7Hg5bAm8IBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFKsuKkLAPhXpZdPy+t4i6Ycl9fxAAAAAAAAAAAAAAAAAAAamzeFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKRYcVMXAAAAAAAAAAAAAAAAAADQlEovn5bX8RZNOS6v4wF4UzgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAigmFAwAAAAAAAAAAAAAAAAAApFhxUxcAAAAAAAAAAAAAAEDzU3r5tLyOt2jKcXkdDwAAAFoSbwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUK27qAgAAAAAAAAAAAAAAACDfSi+fltfxFk05Lq/jAQBALrwpHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYqbugCAhlR6+bS8jrdoynF5HQ8AAAAAAAAAAAAAAAAAoDbeFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBiQuEAAAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAACQYkLhAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBixU1dAAAAAAAAAAAAAAAAAAAANJTSy6fldbxFU47L63hQF94UDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAAClW3NQFAAAAAAAAAAAAAAAAAC1b6eXT8jreoinH5XU8AIC086ZwAAAAAAAAAAAAAAAAAACAFBMKBwAAAAAAAAAAAAAAAAAASDGhcAAAAAAAAAAAAAAAAAAAgBQTCgcAAAAAAAAAAAAAAAAAAEgxoXAAAAAAAAAAAAAAAAAAAIAUEwoHAAAAAAAAAAAAAAAAAABIMaFwAAAAAAAAAAAAAAAAAACAFCtu6gIAAAAAAAAAAAAAAAAAclF6+bSmLgEAoFF5UzgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAABAihU3dQEAhaz08ml5HW/RlOPyOh4AAAAAAAAAAAAAAAAA0PS8KRwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYqbugCA5qT08mlNXQIAAAAAAAAAAAAAAAAAUGC8KRwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFKsuKkLAABoaKWXT8vreIumHJfX8QAAAAAAAAAAAAAAAABq4k3hAAAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAkGJC4QAAAAAAAAAAAAAAAAAAACkmFA4AAAAAAAAAAAAAAAAAAJBixU1dAAD5U3r5tLyOt2jKcXkdDwAAAAAAAAAAAAAAAADInTeFAwAAAAAAAAAAAAAAAAAApJhQOAAAAAAAAAAAAAAAAAAAQIoJhQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKCYUDAAAAAAAAAAAAAAAAAACkWHFTFwAAAAAAAAAAAAAAQMMrvXxaU5cAAAAA1JM3hQMAAAAAAAAAAAAAAAAAAKSYUDgAAAAAAAAAAAAAAAAAAECKFTd1AQCkV+nl0/I63qIpx+V1PFqufB97bJ98/v/h5wAAAAAAAAAAAAAAAADkTigcgEYjZE5L4VgGAAAAAAAAAAAAAAAAGlNRUxcAAAAAAAAAAAAAAAAAAABA9YTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSrLipCwCAlqj08ml5HW/RlOPyOl6+5fvzAgAAAAAAAAAAAAAAAPC/hMIBAAAAAAAAAAAAAAAAAKAJFNrLKam/oqYuAAAAAAAAAAAAAAAAAAAAgOp5UzgAFKB8P0GIdPH/LwAAAAAAAAAAAAAAALQsQuEANFv5Dr4umnJcXscDGp6fAwAAAAAAAAAAQHXcXwQAAEBLUtTUBQAAAAAAAAAAAAAAAAAAAFA9bwoHAGhi+X4aLQAAAAAAAAAAAAAAANCyCIUDAAAAAAAAAAAAANDkvGADAAAAqlfU1AUAAAAAAAAAAAAAAAAAAABQPW8KB4D/L81PGE1zbZCLtB/L+a5v0ZTj8joeAAAAAAAAAAAAAAAAhUkoHAAAAAAAAAAAAAAAACCP0v4yJWgK1gW5cLykhxfwpUdRUxcAAAAAAAAAAAAAAAAAAABA9bwpnBbjnXfeiRdeeCGWLFkSFRUV0bVr1xg8eHCMGDEi2rVr19TlAQAAAAAAAAAAAFTLfZAAAAAA1EQonGZv6tSp8YMf/CBefvnlKr/esWPHOPvss2PixInRo0ePRq4OAICWqPTyaXkdb9GU4/I6HgAAAAAAAADNh/sgAQAAWqZ833MMUNTUBUB9lZeXx5lnnhknn3xytRdCIyLWrVsXv/jFL2Lo0KHxzDPPNGKFAAAAAAAAAAAAAFVzHyQAAAAAufCmcJqlrVu3xqmnnhqPPPJI1vbWrVtHv379onPnzrFw4cJYs2ZN5mtlZWVx7LHHxhNPPBEHH3xwY5cMAEAT86S99PCmdQAAAAAAAKDQuQ8SAAAAgFwJhdMsXXfdddtcCP3a174WEyZMiN69e0fEpxdMH3nkkbj44otj8eLFERHxySefxCmnnBJvvvlmdO7cudHrBgAKi+ArAAAAAAAAAFAV90EC0JK4Vw7INy8CAoCqFTV1AZCrFStWxA9/+MOsbT/+8Y/j5ptvzlwIjYgoKiqKk08+OWbNmhWlpaWZ7UuWLIkbbrihscoFAAAAAAAAAAAAyHAfJAAAAAD14U3hNDs/+clPYu3atZn2oYceGpdddlm1+/fp0yduv/32OOqoozLbbrzxxviP//iP6N69e4PWCgCQT56mCgAAAAAAAADNn/sgAYCG4u3K1JVjZfuk/fuX9voAqD9vCqdZ2bp1a9x1111Z266++upo1apVjf2OPPLIOOSQQzLttWvXxu9///sGqREAAAAAAAAAAACgKu6DBAAAAKC+vCmcZmXWrFlRVlaWaQ8cODBGjRpVp77nnntuPPvss5n21KlT48ILL8x3iQAA5EkhPaUw7Z817W+Vz/f3z+cFAAAAAAAAGor7IAEAAACoL6FwmpVp07LDD6NHj6716Zj/uu+/mjlzZqxfvz46dOiQt/oAAACam3yGzAXMAQAAAAAAoGbug2z50v5geAC2j5/zAAA0paKmLgBy8eqrr2a1R4wYUee+vXv3jtLS0ky7oqIi5syZk6fKAAAAAAAAAAAAAGrmPkgAAAAA6subwmlW5s6dm9UeOnRoTv2HDh0aixYtyhrvgAMOyEdpAADNjieWUleOFZpKvo89bzIHAAAAAACgqbkPEgAAAID6Egqn2diwYUMsXrw4a9uuu+6a0xiV9583b9521wUAALQsQvD1V2jfO6F1AAAAAAAAcuE+SGj+/DsxAAAtSaHd9wktgVA4zcby5csjSZJMu6SkJHr16pXTGH369MlqL1u2bLvrWrZsWZSVleXUZ86cOVnt+fPnb3cdTami7N2mLgEAAKBWb731Vl7Hy/ffQvmuD9Kq8nWQ8vLyJqoEWrbKa6u5X4MEAAAAqCvXIEkz90Gmk3sgaUr+nZiWIs33UPg5DwA0lDT/zuKe2YbVlNcghcJpNtatW5fV3mGHHaJVq1Y5jdGhQ4cax6yPm266KSZNmrRdY5x00knbXQcAAAA12+vOpq6gZmmvDxrKe++9F/vvv39TlwEtznvvvZfVdg0SAAAAKFSuQZIm7oMEKvPvxFA1awMAaA7S/DtLmmuLSH99uWrMa5BFjTIL5EHlC5ft2rXLeYz27dvXOCYAAAAAAAAAAABAQ3AfJAAAAADbQyicZmPjxo1Z7TZt2uQ8Rtu2bbPaGzZs2K6aAAAAAAAAAAAAAOrCfZAAAAAAbI/ipi4A6qryEzErKipyHqO8vLzGMevjoosuinHjxuXU5+OPP46//e1vseOOO0aXLl1i11133eZCbVrNnz8/TjrppEx76tSpsdtuuzVdQVBHjl2aM8cvzZnjl+bM8Utz5dgl7crLy+O9997LtA877LAmrAZarsMOOyymTp2aaTena5D/ynkNtmVdQNWsDaiatQFVszagai1lbbgGSZq5DzJdWsrPPUgT6wryz7qChmFtQf5ZVxSSprwGKRROs9GxY8esduUnZtZF5SdiVh6zPnr16hW9evXKud/BBx+83XOnwW677RZ77rlnU5cBOXPs0pw5fmnOHL80Z45fmivHLmm0//77N3UJ0OJ16dIlxo4d29Rl5J3zGmzLuoCqWRtQNWsDqmZtQNWa89pwDZK0ch9kujXnn3uQVtYV5J91BQ3D2oL8s65o6ZrqGmRRk8wK9VD5wuUnn3wSSZLkNMb69etrHBMAAAAAAAAAAACgIbgPEgAAAIDtIRROs9GjR49o1apVpr1p06ZYtmxZTmMsXbo0q12fJ1sCAAAAAAAAAAAA5Mp9kAAAAABsD6Fwmo327dtHv379srYtXrw4pzEq7z948ODtrgsAAAAAAAAAAACgNu6DBAAAAGB7CIXTrFS+eDlnzpyc+s+dO7fG8QAAAAAAAAAAAAAaivsgAQAAAKgvoXCalWHDhmW1Z82aVee+H3zwQSxatCjTLikpiaFDh+apMgAAAAAAAAAAAICauQ8SAAAAgPoSCqdZOf7447PaTzzxRCRJUqe+jz/+eFb78MMPj44dO+atNgAAAAAAAAAAAICauA8SAAAAgPoSCqdZGTFiRPTo0SPTXrBgQcycObNOfe+4446s9tixY/NZGgAAAAAAAAAAAECN3AcJAAAAQH0JhdOsFBUVxdlnn521bdKkSbU+JfPPf/5zPPvss5l2p06d4pRTTmmIEgEAAAAAAAAAAACq5D5IAAAAAOpLKJxm57LLLouOHTtm2k8//XRce+211e6/dOnSOO+887K2ffOb38x60iYAAAAAAAAAAABAY3AfJAAAAAD1IRROs9OjR4+48sors7ZdccUVcdFFF8X777+f2bZ169aYOnVqjBgxIhYtWpTZ3rt37/jOd77TWOUCAAAAAAAAAAAAZLgPEgAAAID6EAqnWbrsssvi+OOPz9p28803R79+/WLQoEGx//77R/fu3ePkk0+OxYsXZ/Zp3759/P73v48uXbo0csUAAAAAAAAAAAAAn3IfJAAAAAC5Km7qAqA+ioqK4oEHHojx48fH7373u8z2LVu2xIIFC6rs071793jwwQdj5MiRjVVmi9SzZ8+YOHFiVhuaA8cuzZnjl+bM8Utz5viluXLsAtCSOK/BtqwLqJq1AVWzNqBq1gZUzdqAxuU+yKbn5x7kn3UF+WddQcOwtiD/rCtoHK2SJEmaugjYHn/4wx9i8uTJ8eqrr1b59Q4dOsRZZ50VEydOjF69ejVucQAAAAAAAAAAAAA1cB8kAAAAAHUhFE6LMX/+/Jg9e3YsXbo0KioqokuXLjFkyJAYOXJktGvXrqnLAwAAAAAAAAAAAKiW+yABAAAAqIlQOAAAAAAAAAAAAAAAAAAAQIoVNXUBAAAAAAAAAAAAAAAAAAAAVE8oHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYTCAQAAAAAAAAAAAAAAAAAAUkwoHAAAAAAAAAAAAAAAAAAAIMWEwgEAAAAAAAAAAAAAAAAAAFJMKBwAAAAAAAAAAAAAAAAAACDFhMIBAAAAAAAAAAAAAAAAAABSTCgcAAAAAAAAAAAAAAAAAAAgxYqbugCgbt5555144YUXYsmSJVFRURFdu3aNwYMHx4gRI6Jdu3ZNVleSJPHyyy/Hq6++GsuWLYuIiJ122in23Xff2H///aNVq1Z5m2vFihXx/PPPxzvvvBPr16+PDh06xKBBg2LkyJHRvXv3vM1D/jl+ac4K+fgtKyuLN954I955551YtWpVJEkSXbt2jb59+8bnPve56Nat23bPQcMp1GM3SZJYsGBBvPPOO/Hee+/F6tWrY8OGDdGhQ4fo0qVLDB48OIYNGxbt27fPx8ehgRTq8UvL4PgFoJA5D0LV0rY2Nm3aFPPmzYu33norPvroo1i7dm107NgxunfvHvvss0/stddeUVTkudI0vLStDUiLtK+NLVu2xEsvvRRz5syJZcuWxaZNm6Jjx47Rt2/fGDJkSAwePNh5hAaR1rWxevXqePHFF2PhwoWxevXq2Lp1a3Tu3Dn69u0bBxxwQOy8885NVhs0JX+LQ2FJ63m6Jd7b6Odr4bCu3DNM/llXjaclfiaqZ21B/hXyumrs/MLmzZtj9uzZ8eabb8aKFSuidevWscsuu8Tw4cNjzz33zOtckFcJkGoPP/xwsv/++ycRUeV/HTt2TL7xjW8kZWVljVpXRUVFct111yV9+vSptra+ffsm119/fVJRUbFdc7366qvJiSeemBQVFVU5T+vWrZMTTzwxee211/L06ciXQj9+V69encyYMSP54Q9/mIwdOzbZeeedt5ln4cKF+ftg5FUhHr/l5eXJo48+mlxwwQXJbrvtVu34EZG0atUqOfDAA5P77rsv2bRpUwN9WuqjEI/dv/zlL8mll16ajBgxIunQoUONx25EJMXFxcnYsWOTxx9/vIE+LfVViMdvXf3qV7+qcl6/S6RHIR6/Tz31VK0/c2v6r3///g3zoQFodIV4HoS6SNPaWLBgQfKTn/wkGT16dNK+ffsaf0/r3Llz8vWvfz15++23G7wuClOa1kZdrF+/Phk0aNA2dZ511llNXRotTNrXxoIFC5ILL7ww6dKlS43nkR133DEZO3ZsMm3atCapk5YnrWvjD3/4Q3L44YcnrVq1qnFN7Lfffsktt9zi39PIqyVLliQPPfRQctlllyWHH3540qlTp9Rce/W3OBSWtJ6nW+K9jX6+Fg7rqmHX1WGHHbZd/8Z91113bddno2kU+rpqzHuZna8Ki7XVsGvLOaswFeK6aqr8wtq1a5Orrroq6datW7Xz7bHHHsmdd96ZbN26dbvmgoYgFA4ptXHjxuTf/u3f6vxLW8+ePZOnn366UWpbvHhxst9++9W5tuHDhydLliyp11w/+9nPkuLi4jrNU1xcnPz85z/P86elPgr5+P3ggw+Sr371q8ngwYNrvQEgnxdSyJ9CPX7vuuuupGvXrvW6cHDAAQe4STgFCvXYTZIkp89d+b8vf/nLyapVqxruw1MnhXz81sV7772X7Ljjjn6XSKlCPn6FwgEo5PMg1CRNa2Pjxo3JQQcdVK/f19q0aZNcd911/pGbvEnT2sjFt771rSrrEwonX9K+NrZs2ZL86Ec/Stq2bZvTeeTUU09ttBppmdK6NpYvX56MGTMm59+thg8fnvzjH/9o8PpouZ577rnk5JNPTnr37p3aa6/+FofCkdbzdJK0zHsb/XwtDNbVpxp6XQnYFZZCXldNcS+z81XhsLYaZ205ZxWWQl1XTZVfeP3115MBAwbUea5jjjkmWb16db3mgoYiFA4ptGXLlmTs2LHbnEhat26dDBgwIBk2bFjSuXPnbb6+ww47JLNmzWrQ2j766KMq34bQvn37ZM8990yGDBmStGvXbpuv77777jk/jeanP/1plSfUXXbZJRk+fHiyyy67VPn1//zP/2ygT09dFPrx+8orr+T0y6ggV7oU8vH7ne98p9rjtFevXsnee+9d48/eHj16JHPmzGnQ7wHVK+RjN0mqDoW3bt06KS0tTYYNG5YceOCByR577JGUlJRUefzuv//+guFNqNCP37o4/vjj/S6RUoV+/AqFAxS2Qj8PQnXStjbWrl1b7e9j7dq1SwYMGJAccMABydChQ5M2bdpUud9FF12U97ooPGlbG3U1e/bsat9KJRROPqR9bVRUVCTjxo2rcg107tw5GTx4cHLggQcmQ4YMSXbYYYesrwuFsz3SujbWrFlT7Zt6evbsmey///7J8OHDq3wzVMSnb8txTZf6uvHGG1N97dXf4lA40nqeTpKWeW+jn6+Fwbr6VGOsKwG7wlHo66qx72V2vioc1lbjrS3nrMJRyOuqKfILf//735MePXpsM1bHjh2TffbZJ9l9992rvN/84IMPTjZs2FDfbyXknVA4pNCUKVO2OYF87WtfS5YuXZrZZ8uWLclDDz2U9OvXL2u/vn37NugTSI499tis+dq1a5f87Gc/S9avX5/ZZ926dckNN9ywzcn9hBNOqPM8zz//fNK6deus/qNGjUpeeumlrP1efPHFbX7hLS4uTmbPnp23z0xuCv34remPvY4dO+b9Qgr5VcjH77/+UVVSUpKcfPLJyW9+85usz/5Pc+fOTcaPH7/N96pfv35Z9dB4CvnYTZJPQ+EdO3ZMvvzlLye/+MUvkldffTXZuHHjNvtt3LgxefTRR5PPfe5z23y/vvrVr+btM5ObQj9+a/Ob3/wmM2aHDh38LpEyhX78Vg6Ff+UrX0lmzJhR5/+ee+65hvr4ADSCQj8PQnXStjYqh8IHDBiQXH311cnzzz+fVFRUZO37ySefJPfdd1/Sv3//bT7Df/3Xf+W1LgpP2tZGXZSXlyd77bVXtX+XC4WTD2lfG1/5yley5iwuLk6+/vWvJy+88EKydevWrH23bNmSzJ07N/nZz36WjBgxIjnttNMatDZatrSuja9//evb1HXiiScmL7/88jb7zpkzp8qH2o4ePbpBaqPlqykUXvlehKYIhftbHApHWs/TSdIy723087UwWFeNt64q983l37dnzJiRvP/++3X+TDStQl9XjX0vs/NV4bC2Gm9tOWcVjkJeV42dX9i0aVOy9957Z/Xv1q1bcs8992T92/mKFSuSq666apsHR//7v/97neaBxiAUDimzfPnypFOnTlknjh//+MfV7r9kyZKktLQ0a//vf//7DVLb9OnTs+YpKSlJnn766Wr3nzlz5jZPSHnyySfrNNeIESO2+YWgvLy8yn3Ly8uT4447Lmv/Qw89tF6fke3j+P3fP/ZKSkqS4cOHJ1/72teSO+64I3njjTeSLVu25P1CCvlT6Mfvd77znaRTp07JhAkTkg8//LBOdd17771Jq1atGuV7QPUK/dhNkk+f2lZVCLw6W7ZsSc4999xtfia/9dZbdR6D/HD81qysrCzriYRVPRXb7xJNx/G7bSh84sSJefwUAKSZ8yBULY1r45+h8JEjRybTp0/fJsBXlZUrVyYHHHBAVl1dunRJVqxYkdfaKBxpXBt1MXHixMz8ffr0Sb797W9n1SQUzvZK+9q47777subq3bt38tprr9W5/8qVKxusNlq2tK6Njz76aJuQyoUXXlhrv2uuuWab67oN/QYfWqZ/hsI7deqUjBo1Kvnud7+bPPDAA8miRYu2uVbb2KFwf4tD4UjreTpJWua9jX6+Fgbr6lONta4qB+xomayrxr2X2fmqcFhbjbu2nLMKQ6Gvq8bOL9xyyy1Z/bp27VrjveP/+lKniE8fRvT222/XaS5oaM4MkDKXXnrpNhcqartJ64knnsjq06lTp2T58uV5r+3AAw/MmmfChAm19vne976X1WfEiBG19vnjH/+Y1ad79+7JsmXLauzz0UcfJd27d8/q9/jjj9f5s5Efjt8kWbVqVfLXv/612nBiPv/YI78K/fh99tlnk7Kyspxr+9a3vpU1T58+fXIeg+1T6MdufW3cuHGbCyPXXHNNg8xF9Ry/NTv99NMzYw0fPjzZvHmz3yVSxPErFA5QyJwHoWppXBvl5eXJY489lnO/pUuXbvNW5FtvvTVvdVFY0rg2avPmm28mbdq0ycz/8MMPZ4XEI4TC2X5pXhuVH1bYuXPn5B//+Efe54GqpHVt3HHHHVlz9OzZs05voNmyZUsyZMiQrL5XXHFFXmujMMyfPz956623ki1btmzztaYOhftbHApHWs/TSdIy723087UwWFeNu64E7AqDddW49zI7XxUOa6tx15ZzVmEo9HXVmPmF8vLyZNddd83qd8cdd9Ta78wzz8zqc8YZZ+RcLzQEZwZIkS1btiQ9e/bMOmHU9clXhxxySFa/m266Ka+1vf7661njd+jQIfn4449r7ffxxx9vc+PYnDlzauzzxS9+MWv/uj61ZcKECVn9TjnllDr1Iz8cv3WTzz/2yB/Hb/19+OGH2zxt64033sj7PFTNsbt9Lrnkkqx5Tj/99AaZh6o5fmv2P//zP5kxWrdunbz88stJkvhdIi0cv58SCgcoTM6DULU0r436uuiii7Lq+tKXvtTUJdEMNce1sWXLluSggw7KzHvyyScnSZIIhZNXaV8bF198cdYcv/zlL/M+B1QlzWuj8g2aZ555Zp37XnnllVl9x40bl9faoClD4f4Wh8KR5vN0S7y30c/XwmBdfaox7xkWsGv5rKu6+dexIup//1GaPhMNy9qqm3ytrSRxzioE1lX91Se/8Oijj2btX1paWmsAP0k+fVDjv85VUlKSrF69Ol8fBeqtKIDUmDVrVpSVlWXaAwcOjFGjRtWp77nnnpvVnjp1ah4ri3jkkUey2qecckp06tSp1n6dOnWKcePGZW2rqbby8vKYPn161rZzzjmnTjVW3u9Pf/pTVFRU1Kkv28/xS3Pm+K2/nXbaKT7zmc9kbVu8eHHe56Fqjt3tM2jQoKz28uXLG2Qequb4rd7HH38cF154YaZ98cUXx3777ZfzODQcxy8Ahcx5EKqW5rVRX4ccckhW2zUf6qM5ro2f/exnMXv27IiI2HHHHeMXv/hFo8xLYUnz2igvL49777030955553jggsuyOscUJ00r42VK1dmtXfdddc69+3Xr19We/Xq1fkoCVLB3+JQONJ8nm6J9zb6+VoYrCv3DJN/1lXjaomfiapZW5B/1lX91Se/UPkzjR8/Plq1alXrXIMGDYrDDjss0960aVP88Y9/zKFaaBhC4ZAi06ZNy2qPHj26TieZf+77r2bOnBnr169vsNqOPvroOvetXNtjjz1W7b6V695jjz2if//+dZqntLQ0dt9990x77dq18fTTT9e5TraP45fmzPG7fbp27ZrVXrNmTYPMw7Ycu9tn48aNWe0uXbo0yDxUzfFbvUsvvTSWLFkSEZ/+jnvNNdfkPAYNy/ELQCFzHoSqpXlt1JdrPuRDc1sbCxYsiAkTJmTaP/7xj6N3794NOieFKc1r4+GHH84Kv5522mnRunXrvI0PNUnz2ujcuXNWe8OGDXXuW3nfHj165KUmSAN/i0PhSPN5uiXe2+jna2GwrtwzTP5ZV42rJX4mqmZtQf5ZV9sn13/Lbg6fCXIhFA4p8uqrr2a1R4wYUee+vXv3jtLS0ky7oqIi5syZk5e6kiSJ119/vd61jRw5Mqv92muvRZIkVe67Pd+DquaqPB4Nx/FLc+b43T5Lly7Nanfv3j3vc1A1x+72+ecbn/5p+PDheZ+D6jl+q/b000/HrbfemmnffPPNscMOO9S5P43D8QtAIXMehKqldW1sD9d8yIfmtjbOP//8+OSTTyIi4uCDD44LL7ywQeejcKV5bVS+Merwww/P29hQmzSvjWHDhmW1X3zxxTr3feGFF7LaBx54YD5Kgibnb3EoLGk9T7fEexv9fC0c1pV7hsk/66rxtMTPRPWsLcg/62r75PJv2R999FF8+OGHmXbbtm1j//33r/NcfuckjYTCIUXmzp2b1R46dGhO/SvvX3m8+nr33XczN8BERHTo0CH69etX5/79+/fPCrKsX78+3nvvvSr3Tev3gNql9f+7xjx+ab4cv/W3cOHCzNts/+lfn8BKw3Ls1t/cuXPjoYceyrSLi4vjjDPOyOsc1Mzxu60NGzbE+eefn7kAdvrpp8cXvvCFOs9N43H8Vi9JkliwYEH89a9/jeeffz7mzp0bq1atymkMANLNeRCqlta1sT2effbZrPZnPvOZJqqE5qw5rY3bb789nnzyyYiIKCkpidtuu63Ob2SAXKV5bVQOuu67774REbFly5b405/+FKeddlrsscce0aFDh+jSpUvsvvvuccopp8Rdd92V9fsY1Eea18bxxx8fHTp0yLSff/75+Mtf/lJrv/nz58cf/vCHTLtdu3b+PYIWw9/iUFjSep5uifc2+vlaOKyrdHwP1qxZE6+//no888wz8fLLL8e7774bW7ZsyXkc0iENx1RVWuLP9pb4maietZUOzlkti3VVf7nmFyp/b3bbbbdo06ZNneer/L2eP39+bN68uc79oSEIhUNKbNiwIRYvXpy1bdddd81pjMr7z5s3b7vrqmqcXOuqqk91tW3vXA31PaBmjl+aM8fv9rn77ruznt41ZMiQGDBgQF7noGqO3fqbPXt2HHPMMVFRUZHZdtVVV9WrTurH8Vu1iRMnxj/+8Y+IiOjWrVv87Gc/y3luGp7jt3r33HNP9OjRIwYNGhQHH3xwfP7zn4+hQ4dGt27dYsiQIfH1r3893nrrrZxrAiA9nAehamleG/X18ccfx4MPPpi1bcyYMU1UDc1Vc1obH3zwQXz3u9/NtC+99NLYc889G2QuSPPaWLNmTbz99tuZduvWraN///6xYMGCOOSQQ2LMmDFx//33x9tvvx2ffPJJrFmzJubPnx8PPPBAnHPOObH77rvHfffdl5daKDxpXhsREV26dIkrr7wya9uXvvSlGt8YPnfu3BgzZkzWv0dMnjw5evXqlbe6oCn5WxwKR5rP0y3x3kY/XwuDdZWfubb3e7DffvtFt27dYt99943DDjsshg8fHqWlpdGlS5f4whe+ELfddluUl5fnNCZNx7pqXC3xM1E1aysdnLNaFutq++SaX9jez9SzZ89o165dpl1RURELFy7MaQzIN6FwSInly5dnnZRKSkpy/ofAPn36ZLWXLVuWl9oqj9O3b9+cx6hrbds7V0N9D6iZ45fmzPFbfx988ME2gcWzzz47b+NTM8du9crKyuKJJ57I/Pf444/HH/7wh5gyZUocccQRcfDBB2c9de5rX/taTJw4MecaqT/H77ZeeumluOGGGzLt6667zo2BKeX4rd6iRYti5cqVVX7t73//e9x0002x9957x7hx46rdD4B0cx6EqqV5bdTX5MmTY926dZl2jx494vjjj2/CimiOmtPauOiii2L16tUR8embBL73ve81yDwQke61sWDBgqzaOnXqFHP+X3t3HmVVdSYK/KtiHsMkIA6MAu3AGBFDDMQxHcHWRBNjFIfYiiYmcWzjIyqJ6Y5xwNUvmqfYEZ+GJAajGJGotKKiJtHEoVFUZHJAmWSQGeG8P3xcuVVF1a2qW3VP1f391qq12KfOPvs7l/3VqfvV2ee+/noMGzYsp09EXrZsWYwfPz6uvPLKvMRDcUlzbuxy5ZVXZn3K9wcffBCHH354/Mu//Evceuut8fDDD8fMmTPjjjvuiFNPPTUGDx6ceRDorv6XXnppXmOCQvJeHIpHmq/TjfHeRj9fi4O8ys9YtX0NXn755di5c2e57Rs2bIhHH300zjvvvOjVq1f84Q9/qNZxKQx5Vb8a4zlRMbmVDq5ZjYu8qrmarF/Ixzn16NGj0mNCfWta6ACAT+1+c1VEROvWraOkpKRax2jTpk2lx6ypsscpO04uco2ttmPV1WtA5cxfGjLzt2aSJIlzzz031q9fn9m2zz77xHe/+928HJ+qmbt79uyzz8ZJJ51U5X6HHHJITJo0Kad9yS/zN9v27dvjO9/5TuzYsSMiIsaMGRPnnHNOtcelfpi/tZMkSUyfPj3+9re/xaxZs+LAAw/M6/EBqFuug1CxNOdGTTz33HNZD62KiJg4cWK0bt26QBHRUDWU3LjvvvviwQcfzLRvv/32rKf9Q76lOTd2PRxhl5KSkhg7dmysW7cuIj6N9bTTTosvfelL0blz51i9enU89dRTMW3atNi8eXOm3/XXXx/77LNPXHTRRXmJi+KQ5tzYpbS0NO699974whe+EJMmTYqVK1fGjh074qGHHoqHHnpoj/1GjRoVkyZNiqOOOiqv8UCheS8OxSPN1+nGeG+jn6/FQV7lZ6z6mOsffvhhfOMb34jLLrssbrjhhrwfn/yRV/WrMZ4TFZNbDYdrVsMhr2qmpusX0nxOUFM+KRxSouwFoSY3m7Rq1arSY9ZUfcZW27Hq6jWgcuYvDVma50iaY/v5z38ejzzySNa22267rUZvkqiZNM+PNMe2y7Bhw+Lqq6+OcePG5fW45CbNc6QQsV1//fXxyiuvREREixYt4vbbb6/2mNQf87e8/v37xyWXXBIzZsyIt99+O9avXx/bt2+PFStWxNy5c+Oaa66J7t27Z/V555134qtf/WosX7682jECUDiug1CxxjT/VqxYEaeeemrmoVUREYceemh873vfK0g8NGwNITdWr16dtWj17LPPji9/+ct5HQPKSnNulF0UvmbNmli8eHFERAwfPjzmz58fU6ZMiTPOOCO++tWvxhlnnBF33nlnvP766zFo0KCsvpdffnm89dZbeYmL4pDm3NhdSUlJfPe7341//OMfMXbs2Cr3HzVqVFx66aWuLzRKDSVvgdpLc743xnsb0/x6kz9p/n9ujHlVdoxx48bFbbfdFs8991ysWLEitm3bFh9//HEsXLgw7r333jj++OPLLcy68cYb4+c//3m14qN+yav61RjPiYql+f86zbHlg2tW45XmuZvm2Gq6fiHN5wQ1ZVE4pMSWLVuy2s2bN6/2MVq0aJHV3v1p7LVRn7HVdqy6eg2onPlLQ5bmOZLW2GbMmBETJ07M2jZhwoQ44YQTan1scpfW+RGR7th2+cc//hGnnHJK9OvXLx599NG8HpuqpXmO1Hds8+fPj+uuuy7TnjhxYvTv37/aY1J/zN/P9OrVK5588sl4880346abbooTTjgh+vbtG+3atYumTZvGXnvtFaNGjYprr702Fi9eHOeff35W/6VLl8aFF15Y7RgBKBzXQahYY5l/W7dujZNOOinefffdzLZ27drFtGnTokmTJvUeDw1fQ8iNH/7wh7FixYqIiOjatWvceOONeT0+VCTNubGnm5j23XffePzxx2P//fev8Pu9evWK//7v/856KNzWrVvlFNWS5tzY3caNG+OSSy6J/v37x8MPP1zl/s8++2x87Wtfi4MOOij+8pe/5D0eKKSGkrdA7aU53xvjvY1pfr3JnzT/PzfGvNrlkksuiffeey8eeuihuOCCC+Lwww+PvfbaK5o1axZt27aNPn36xLe//e14+OGH4+mnn4599tknq/9VV12Veeg/6SOv6ldjPCcqlub/6zTHVluuWY1bmuduWmOrzfqFtJ4T1IZF4ZASZZ80sm3btmofY+vWrZUes6bqM7bajlVXrwGVM39pyNI8R9IY21/+8pc47bTTYufOnZltRxxxRNxyyy21Oi7Vl8b5safj1HdsJ554YiRJkvna9Wm1c+bMiYkTJ2bdmLh06dL453/+55gyZUq1Y6TmCj1HKlOfse3cuTO+853vZPY/6KCD4t/+7d+qPR71y/z9TK9evWLMmDE5x/Z//s//iR/+8IdZ2//4xz/Giy++WN0wASgQ10GoWGOYfzt37ozTTz89nnvuucy2Jk2axG9+85vo169fvcZC45H23Jg1a1bce++9mfbkyZOjU6dOeTs+7Emac2NPx7nhhhuiY8eOlfbt0qVLuU+fueeee9wYRc7SnBu7LFu2LD7/+c/H5MmTM3N7wIABcdttt8Ubb7wRGzZsiE2bNsXChQtj6tSpMXz48EzfN954I4444oh48MEH8xoTFFJDyFsgP9Kc743x3sY0v97kT5r/nxtjXu1ywgknROfOnXM69he/+MWYM2dOdOnSJbMtSZJyi5FID3lVvxrjOVGxNP9fpzm22nLNatzSPHfTGFtt1y+k8ZygtiwKh5Ro27ZtVrvsk0hyUfYP6mWPWVP1GVttx6qr14DKmb80ZGmeI2mL7bXXXovjjz8+Nm3alNk2ePDg+NOf/lTu6VfUvbTNj8qOU+jYdn1a7ejRo+OnP/1pvPXWW3Haaadlvp8kSVxwwQU+oaMepW2OVHacuoztf//v/x3PP/98RESUlJTEHXfcEc2aNav2eNQv87d2brjhhnKLinZfhAFAuqX5WpPm2Gj8GsP8u/DCC2P69OmZdklJSUyZMiXGjRtXr3HQuKQ5Nz7++OOYMGFCpv2Vr3wlq14EdSnNuVHRcTp16hRf//rXc+r/zW9+Mz73uc9l2lu2bIm//e1veYmNxi/NuRHxaTzHHntsvPHGG5lt5557brz66qtxwQUXxIABA6JNmzbRqlWr6NOnT5x55pnxwgsvxP/6X/8rs/8nn3wS3/rWt2L+/Pl5iwsKKe15C+RPmvO9Md7bmObXm/xJ8/9zY8yrmurXr1/ccMMNWdseeeSR+Oijj/I6Dvkhr+pXYzwnKpbm/+s0x1bfXLMaljTP3bTFlo/1C2k7J8gHi8IhJcpeEDZt2hRJklTrGBs3bqz0mDVV9jhlx8lFrrHVdqy6eg2onPlLQ2b+5mbx4sVx7LHHZhUHDjjggHj00UezbvCi/pi7NdeuXbu455574vjjj89s27FjR1x66aV5G4PKmb8RS5YsyboZcMKECfGFL3yh2mNR/8zf2mnatGl8//vfz9r22GOP5XUMAOqO6yBULM25kYsf/ehHcfvtt2dtu+mmm+Lss8+utxhonNKcG1deeWW88847ERHRunXr+NWvfpWX40Iu0pwbFR3n8MMPz/lBhi1btowRI0ZkbXvxxRfzEhuNX5pzIyLi+uuvj9deey3TPvLII+P222+P5s2b77FPSUlJXHfddXHGGWdktm3ZssXfI2g0vBeH4pHm63RjvLfRz9fiIK/yM1Z9zPXx48fHXnvtlWnv3LkzZs+enfdxqD15Vb8a4zlRMbnVcLhmNRzyKjf5Wr+QpnOCfLEoHFKiS5cuUVJSkmlv3749VqxYUa1jvP/++1ntrl275iW2ssd57733qn2MXGOr7Vh19RpQOfOXhsz8rdqyZcvi6KOPjmXLlmW27bfffjF79uzo1q1btY9Hfpi7tVNaWhr/+Z//mfUaPvfcc7FgwYK8jkPFzN+Ia6+9NlMk6tGjR/z85z+v9jgUhvlbe0cddVRWe8GCBdUuagNQGK6DULE050ZVfv7zn5d7P3L11VfHxRdfXC/j07ilNTcWL16ctQh80qRJ0atXr1ofF3KV1tyIiApr/v3796/WMQYMGJDVru65UbzSnBs7duyIX/7yl1nbrrvuuigtze22q5/97GdZ+/75z3+Od999Ny+xQSF5Lw7FI83X6cZ4b6Ofr8VBXuVnrPqY66WlpTFmzJisbW+++Wbex6H25FX9aoznRMXkVsPhmtVwyKuq5XP9Qj7Oafc4Kjom1DeLwiElWrVqFfvvv3/Wtl2fUJCrsvsPHDiw1nFFlP/DfU3+OFm2z55iKztWWl4DKmf+0pCZv5VbtWpVHH300bFo0aLMtq5du8bs2bPLvW7UL3O39vr06RODBw/O2vbcc8/lfRzKM38j1q5dm/n3smXL4nOf+1yUlJRU+VVW7969s75/yy23VDteqsf8rb399tsvq/3JJ5/EmjVr8j4OAPnnOggVS3NuVObWW2+NH/3oR1nbfvCDH8SkSZPqfGyKQ1pzY926dVkPprr88stzek9eNjfuvvvurO936NCh1rFRHNKaGxERffv2Lfepx+3bt6/WMcru7z0/uUpzbrz66quxatWqTLtLly4xcuTInPvvt99+WX+PSJIk5s6dm5fYoJC8F4fikebrdGO8t9HP1+IgryoeKy2vQVll/8a9cuXKOhmH2pFX9asxnhMVk1sNi2tWwyCvKpfv9Qu1/Z1zxYoVsWXLlky7efPm0adPn2rHAflkUTikSNkL3euvv16t/vPnz6/0eDXVs2fPaNWqVaa9cePGWLp0ac79ly5dGps2bcq027RpU+6XzV3S+hpQtbT+39Xn/KXhMn8rtm7dujjuuOOyzq9Dhw7x2GOPVfuTQagb5m7t9e3bN6v94Ycf1sk4lGf+0pCZv7XTrFmzctu2b9+e93EAqBuug1CxtObGnvzf//t/46KLLsrads4558TkyZPrdFyKT0PLDagvac2NJk2alKv/b926tVrH2P3GqIiI1q1b1zouikdac2Px4sVZ7V69elX4EM/K9O7dO6td9tNyoCHyXhyKS1qv043x3kY/X4uHvErva1BW2b9x+/t2eqV1TjXGn+2N8ZzYM7nVcLhmNRzyqmJ1sX6h7GuzcOHC2LZtW879y77Wffv2jaZNm9YoFsgXi8IhRYYMGZLVrs4nVX7wwQexZMmSTLtZs2Zx4IEH5iWukpKSGDRoUI1je/bZZ7PagwYN2uMfSGvzGlQ0VtnjUXfMXxoy87e8jRs3xvHHHx//+Mc/Mtvatm0bs2bNKvfJyhSOuZt/FS1UpG6YvzRk5m/tlH0AR0lJSXTu3Dnv4wBQN1wHoWJpzY2K3H///XHOOedkfVLyN77xjZgyZYp5T941pNyA+pTm3Bg2bFhWe/ny5dXqv2LFiqy29/xUR1pzo+zDEWpyw1/Zvz/s2LGjVjFBGngvDsUlrdfpxnhvo5+vxUNeNZx7hsv+jXuvvfaqk3GoPXlVfxrjObFncqvhcM1qOORVeXW1fqF79+7RvXv3THvr1q3x97//Pef+1qmRRhaFQ4qMHTs2qz179uysm7Iq89hjj2W1v/zlL0fbtm3rLLbHH388575l9x03btwe9x0zZky0adMm037rrbdyfqrMkiVLYsGCBZl2u3btYsyYMTnHSe2YvzRk5m+2rVu3xoknnpj1BqZly5YxY8aMGDlyZM7jU/fM3dor+3tGt27d6mwsshX7/P3JT34Sjz/+eLW/yrr33nuzvv/1r38951ipuWKfv7U1d+7crPbee+/tyZkADYjrIFQszbmxu1mzZsVpp52WtQjp+OOPj3vvvTdKS/3ZkPxLY27069evRu/JzzjjjKzjHHvssVnfnzFjRq1jo3ikMTd2OeGEE7La1bkxqqL9BwwYUOuYKB5pzY2yDzdYtmxZtY9R9pPB3ZBLY+G9OBSPtF6nK4qtMdzb6OdrcZBXDeee4bJ/427onyLbmMmr+tUYz4mKya2GwzWr4ZBX2ep6/cLxxx9faZyVaYw/K2gEEiA1duzYkXTp0iWJiMzXE088kVPfI444IqvfrbfemtfYXnnllazjt23bNvn444+r7Ld+/fqkTZs2WX1fe+21SvucdNJJWftfffXVOcX44x//OKvfKaecklM/8sP8zc3ux4qIZPHixbU6Hvlh/n5m+/btyQknnJDVr1mzZsmf/vSnfJwOeWbu1s7777+flJaWZo316quv1slYlGf+1ozfJdLB/K2dMWPGZI1zxhln1Mk4ANQN10GoWJpzY5c5c+YkrVq1yhrry1/+crJ58+Y6GQ+SpGHkRq6uueaarHjOPPPMgsZDw5bm3NiwYUPSsmXLrDHeeuutnPrOmzevXP1q+fLleY2Pxi2tufHmm2+Wm9tvv/12zv3Xr1+ftGjRIqv/nDlz8hYfPPnkk1nzq2fPnvU2tvfiUDzSep1OksZ5b6Ofr8VBXn0q7fcMz5kzp9z7gYULF9bJWNSevMpN2Tld0/uP0nRO1C25lZt85VZNuWY1LPLqM/WxfmHGjBlZx+/Vq1eyc+fOKvu9/fbbSUlJSVZca9euzVtcUFMWhUPKXHbZZVkXmtGjR1d5oZk9e3ZWn3bt2iUrV67Me2yHHnpo1jg//vGPq+wzceLErD4jR46sss/DDz+c1adz587JihUrKu2zfPnypHPnzln9/vznP+d8buSH+Vu1Qr/ZY8/M30/fXH7729/O6ldaWpr8/ve/z8dpUEfM3Zo744wzssbq3bt3nY1Fxczf6vO7RHqYvzVzzz33lJvH999/f52MBUDdcR2EiqU5N1544YWkXbt25eZ6Ln+8h9pKc25Uh0Xh5Fuac+Pcc8/NGmf8+PE59fvGN75R7pygutKaG/vuu2/WGBMmTMi577XXXpvVt3Xr1smWLVvyGh/FrZCLwpPEe3EoJmm9TidJ47y30c/X4iCv0n3P8IYNG5JBgwZljXPIIYfkfRzyS15Vrex9G7W5/ygt50Tdk1tVy2duVZdrVsMkr+pv/cKWLVvK1Xj/67/+q8p+p59+elafU089Na9xQU1ZFA4ps3LlyqRt27ZZF43/+I//2OP+7733XtKrV6+s/SdOnFjlOGV/4XzyySer7DNr1qysPs2aNUueeuqpPe4/Z86cpFmzZll9Zs+eXeU4SZIkI0eOzOo3bty4ZNu2bRXuu3Xr1mTs2LFZ+x9xxBE5jUN+mb9VK+SbPSpn/ibJhAkTsvqUlJQkv/71r6vsR2EV+9y97bbbkt///vc5Pa1tl+3btyeXX355uXMq9KdNFaNin7814XeJ9Cj2+fvb3/42uf/++6v183fatGnlPhFpyJAh1ToGAOlQ7NdB2JO05sa8efPK3SA5ZMiQZM2aNdU8Q6iZtOZGdVkUTr6lOTfefffdcp8WXtXNUbfeemu5sTzEm5pIa25ceeWVWfuXlJQkd999d5XjPPTQQ0nTpk2z+p5zzjlV9oPqyOeicO/Fgcqk9TqdJI3z3kY/X4uDvPpUfeTV97///eT999/PKZ4k+fT/5sgjjyz32v3xj3/M+RgUhryqWtnYa3P/UVrOibont6qWr9xyzSoe8qp+1y/86le/yhqrY8eOlX6S+W9+85us/Zs0aZK8+eabdRIbVJdF4ZBC//7v/17uonvBBRdk/WK3Y8eO5IEHHkj233//rP169OiR041cNbmoJ0mSHHvssVn9WrZsmdxyyy3Jxo0bM/ts2LAhmTx5crkbBb761a/m/Bo888wzSWlpaVb/MWPGJH//+9+z9nvxxReT0aNHl7vQPv/88zmPRX6Zv0ny2muvJY8//niFX2Vjv/feeyvcb+7cuTmPR/4U8/wt+wkFEZGcfPLJe5zLlX0tXLgwp3Mif4p57v7gBz9IIj79lO8rr7wyefrpp5P169dXuO8HH3yQ3H777cnBBx9c7nwOO+ywZMeOHTmdE/lVzPO3Jsqei0XhhVXM83fXYoh+/folV111VfLcc88lGzZsKLff1q1bk//+7/9OTjjhhHLn0rJlS+/dABqwYr4OQmXSlhvLli1LevTokbV/mzZtkmnTptWo7gM1lbbcqAmLwqkLac6NsnO+pKQk+e53v5u88847WfstXbo0mTBhQlJSUpK1/7e+9a3qvBSQJY258dFHHyWdOnUq1++ss85K5s2bV27/BQsWJN/73vfK3ffQunXrZMmSJdV9SSBJkiSZO3duhb+n33jjjVnzrFu3bnv8nb6yG12TxHtxoGppvE7v0hjvbfTztTjIq/rJq4hIWrRokZx44onJvffeu8f7Ld55553kF7/4RdK9e/dyr9uJJ56Y8zlRWPKqfu9ldr0qHnKrfnLLNau4FHNe1ff6hW3btiUHHXRQ1nidOnVK7r777mT79u2Z/VavXp1MnDix3O+nF154YU6vG9QHi8IhhXbs2FHuKXa7Chd9+vRJhg4dmnTo0KHc91u1apXzm6+aXtQ//PDDpHfv3hWOfdBBByUHHnhguYt5RCR9+/ZNVqxYUa3X4frrry93nF2/uAwfPjzZe++9K/z+TTfdVK1xyC/zN0nOPPPMCudmdb5q8+Ruaq6Y52/ZYnltvq655pqczon8Kea5u2tR+O5fJSUlyb777psccsghyciRI5NDDjkk6dq16x7n7JAhQ5LVq1fndD7kXzHP35ooO5ZF4YVVzPO37I3hEZGUlpYm+++/fzJo0KDksMMOSwYOHFjhGBGfPjn0/vvvz+lcAEinYr4OQmXSlhtlPzGwtl9QU2nLjZqwKJy6kObc+OSTTyqMraSkJOnTp09y6KGHJn369KnwejFs2LDk448/rsUrQ7FLa2489dRTSYsWLSqc9127dk2GDRtW6b0MpaWlyYMPPljLV4di1rNnz1r/Tl/V7zDeiwNVSet1Okka572Nfr4WB3n1qbrOq4r6tm/fPhkwYEAyYsSIZOjQoeUesLn71xFHHJFs2rSpWudE4cir+r2X2fWqeMit+skt16ziUsx5VYj1C6+//nqFD/9s27ZtMnjw4KR///7lPvE8IpIRI0bIK1LF3RuQUps3b05OPfXUnC9gnTt3rtbNLTW9qCdJkixZsiQZPHhwzrENGTKk3BPjc3XjjTcmTZo0yWmcJk2aJJMnT67ROORXsc9fi8IbtmKdvxaFN3zFOncrWhSe61dpaWly0UUXuTkxBYp1/tZE2fEsCi+8Yp2/FS0Kz/Wrf//+yYsvvpjzeQCQXsV6HYSqpCk3LAonTdKUGzVhUTh1Jc25sWXLlmr/3euEE05QcyUv0pobzzzzTI0W5nbr1i2ZOXNmzV4M+P/SvCg8SbwXh2KS1ut0kjTOexv9fC0O8upTdZlXNf39qbS0NLniiiuSbdu21eicKJxiz6v6vpfZ9ap4yK3CLAp3zWrcijWvCrV+4eWXX65Wne3oo4/O6RPZoT65ewNSbvr06cmQIUP2eHFp06ZNcuGFFybLly+v1nFrc1FPkiTZunVrcv3111f6hKEePXokv/jFL5KtW7dW69hlvfTSS8nxxx+flJaW7vGX17FjxyYvv/xyrcYh/4p1/loU3jgU2/y1KLzxKLa5++GHHyZ33nlncvLJJ1d67N2/9tlnn+TSSy9N5s+fX61zoO4V2/ytibLjWhSeHsU2f1977bXkRz/6UXL44YcnrVq1qvJnb9OmTZMjjjgimTZtmj88ADRCxXYdhFylITcsCieN0pAbNWFROHUtzbkxa9asZNSoUXuMraSkJDnssMOSP/3pT9U+NlQljbmxfv36ZPLkycnAgQOr/P2pV69eyXXXXZesWrWqmmcO5aV9UXiSeC8OxSaN1+kkaZz3Nvr5WjzkVd3l1R133JGceuqpyX777ZfT703du3dPfvCDHyQLFiyo1flQeMWaV4W4l9n1qrjIrbrLLdes4lVseVXI9Qvr169PfvSjHyUdO3bc4zEPOOCAZMqUKcnOnTurdWyoDyVJkiQBpN7bb78df/3rX+P999+Pbdu2RYcOHeKf/umfYtSoUdGyZcuCxbVz5874+9//Hq+88kqsWLEiIiK6du0aQ4YMiWHDhkVpaWnexlq1alXMnTs3Fi1aFBs3bow2bdpE3759Y9SoUdGlS5e8jUP+mb80ZOYvDVWxzt33338/3nzzzVi8eHGsWbMmNm/eHG3atIn27dvH3nvvHUOHDo0ePXrk41SoQ8U6f2kcinH+7tixI958881YtGhRvPfee7F+/frYtm1btG3bNjp27Bi9e/eOQw89NFq1apWv0wEgpYrxOgi5SGtuQKHJDahYmnPj/fffj+effz6WLl0aW7ZsiY4dO8bee+8do0aNiq5duxY0Nhq/tObGhx9+GC+88EIsW7Ys1q5dG0mSxOc+97no1q1bfP7zn4/999+/YLFBIXkvDsUlrdfpxnhvo5+vxUNe1W1erV69OubPnx9Lly6NlStXxsaNG6NJkybRsWPH6NKlSwwdOjT69OmTpzMhLeRV/WmM58Seya265ZpVnORV/dm+fXv89a9/jXnz5sXq1aujSZMmsffee8ewYcPikEMOKXR4sEcWhQMAAAAAAAAAAAAAAAAAAKRYw3sEAwAAAAAAAAAAAAAAAAAAQBGxKBwAAAAAAAAAAAAAAAAAACDFLAoHAAAAAAAAAAAAAAAAAABIMYvCAQAAAAAAAAAAAAAAAAAAUsyicAAAAAAAAAAAAAAAAAAAgBSzKBwAAAAAAAAAAAAAAAAAACDFLAoHAAAAAAAAAAAAAAAAAABIMYvCAQAAAAAAAAAAAAAAAAAAUsyicAAAAAAAAAAAAAAAAAAAgBSzKBwAAAAAAAAAAAAAAAAAACDFLAoHAAAAAAAAAAAAAAAAAABIMYvCAQAAAAAAAAAAAAAAAAAAUsyicAAAAAAAAAAAAAAAAAAAgBSzKBwAAAAAAAAAAAAAAAAAACDFLAoHAAAAAAAAAAAAAAAAAABIMYvCAQAAAAAAAAAAAAAAAAAAUsyicAAAAAAAAAAAAAAAAAAAgBSzKBwAAAAAAAAAAAAAAAAAACDFLAoHAAAAAAAAAAAAAAAAAABIMYvCAQAAAAAAAAAAAAAAAAAAUsyicAAAAAAAAAAAAAAAAAAAgBSzKBwAAAAAAAAAAAAAAAAAACDFLAoHAAAAAAAAAAAAAAAAAABIMYvCAQAAAAAAAAAAAAAAAAAAUsyicAAAKCJnnXVWlJSUZL6WLFlS6JBSberUqVmvV0Vfc+bMKUhsVcV11llnFSQuAAAAAIqbGmT1qEECAAAAQPWoQVaPGiQANC4WhQMAAAAAAAAAAAAAAAAAAKRY00IHAABAevXq1SuWLl1a6T4tWrSIFi1aROfOnaN79+5xwAEHxEEHHRSjRo2KESNGRLNmzeopWgAAAACgoVGDBAAAAADqkhokAACNiUXhAADUytatW2Pr1q2xfv36WLx4cTz//POZ73Xo0CG+9rWvxUUXXRRDhgwpXJCNSElJSebfo0ePjjlz5hQumCJ0+eWXx7HHHpu1bfDgwQWJ5fHHH89qL1++PE4//fSCxAIAAABQl9Qg65caZGGpQQIAAADUPzXI+qUGWVhqkADQsFkUDgBAnVm7dm38+te/jl//+tdx8sknxy233BL77LNPocOCGjvwwAPj6KOPLnQYERHl4liyZElhAgEAAAAoIDVIGhs1SAAAAIB0UYOksVGDBICGzaJwAAByduONN5Z7GuD27dtjzZo1sXbt2li6dGk8//zz8eKLL8bmzZuz9ps+fXrMmTMn/vCHP8SYMWPqMWp2N3Xq1Jg6dWqhwwAAAACACqlBNnxqkAAAAACkmRpkw6cGCQAUM4vCAQDI2fDhw3MqZG7evDnuueeeuOWWW2L+/PmZ7atWrYqvfvWrMWvWrBg9enQdRgoAAAAANERqkAAAAABAXVKDBACgISstdAAAADQ+rVq1ivPOOy9effXVuPjii7O+t3nz5jjllFPigw8+KFB0AAAAAEBDpwYJAAAAANQlNUgAANLIonAAAOpM06ZN4+abb46bb745a/vKlSvj8ssvL1BUAAAAAEBjoQYJAAAAANQlNUgAANKkaaEDAACg8bv44ovjmWeeiQceeCCzbdq0afHjH/84BgwYUMDIcrNhw4Z49tlnY9myZfHhhx9Gy5YtY/To0TFs2LA99tmyZUu8/vrrMX/+/Fi5cmVs3Lgx2rVrF507d45DDjkkDj744CgtbZjPaFq7dm3m9Vi1alW0bds2unbtGkOHDo3+/fvnfbwVK1bEM888E4sXL47t27dHly5d4sADD4yRI0dGkyZN8j5eXdq+fXv8z//8T8ybNy9Wr14dGzdujBYtWkS7du2iZ8+e0b9//+jbt2+hwwQAAABocNQg1SBrQw0SAAAAgKqoQapB1oYaJACQLxaFAwBQL2688caYMWNG7Ny5MyIikiSJ22+/vdzTM3eZOnVqnH322Zn2XXfdFWeddVbO45WUlGT+PXr06JgzZ84e9x0zZkw89dRTmXaSJBER8frrr8d1110XM2bMiE2bNmX1+cEPflCuGPree+/F7373u5g5c2Y8//zzsXXr1j2O2bFjxzj77LPj0ksvjR49elR6LmXj2+Wpp57KOs+yrrnmmrj22muztp111llx9913Z9qLFy+OXr16VTr+Lk8//XRMmjQpnn766fjkk08q3Kdfv35x4YUXxne/+91o3rx5Tsft1atXLF26NCIievbsGUuWLImIiLfeeiuuvPLKrHmzu86dO8dVV10VF110UTRr1iynsQrlww8/jOuuuy6mTZsWa9asqXTfLl26xJFHHhnnnHNOHHfccfUUIQAAAEDDpwaZTQ3yM2qQ2dQgAQAAAGpGDTKbGuRn1CCzqUECQN1pmI/kAQCgwenTp0+MGzcua9uDDz5YmGBy8Jvf/CaGDh0av/3tb8sVQivy6quvxv777x+XX355zJkzp9JCaETEmjVr4uabb44DDzwwZs2ala+w68S2bdti/PjxMXr06HjiiSf2WAiNiHj77bfjkksuiYMPPjjeeOONGo85ffr0GDJkSDzwwAMVFkIjIlavXh2XXnppnHTSSbFly5Yaj1XXHn/88Rg4cGDceuutVRZCIyJWrVoV9913X/z0pz+th+gAAAAAGg81yGxqkJVTg1SDBAAAAKguNchsapCVU4NUgwSAumBROAAA9eZrX/taVnvx4sWZJyOmySOPPBLjx4+Pbdu2RUREaWlp9O3bNw499NDo2bNnNGnSpFyfbdu2ZZ6suUvz5s2jb9++MXTo0BgxYkQccMAB0bRp06x91q1bF2PHjo0nn3yy7k6oFrZu3RrHH3983HPPPeW+t/fee8fnP//56N+/f7knVC5YsCC++MUvxksvvVTtMWfOnBmnnnpqbN68OSIimjVrFv37948RI0ZU+DTPmTNnxhVXXFHtcerDa6+9FuPGjYt169ZlbW/RokUMGDAgRowYEcOHD49+/fql/imfAAAAAA2BGqQaZC7UIAEAAACoKTVINchcqEECAHWladW7AABAfhx22GHltr300kvRs2fPAkSzZ+ecc07s3LkzPve5z8XVV18d48ePjy5dumS+v3z58j0WcUePHh0nnnhiHHPMMTFgwIByxc8tW7bEo48+Gv/+7/8ef/vb3yIiYufOnXH66afHm2++GW3bti13zJtuuinzZMVjjjkms33QoEFx00037fE8+vTpk/tJ78FVV10Vs2fPztp24oknxqRJk2LQoEGZbR999FH813/9V1xzzTWZIubq1avjlFNOiZdffrnC86rIunXr4owzzogdO3bEvvvuGz/5yU/i5JNPjnbt2mX2WbBgQVx88cUxc+bMzLZbb701zj///DjooINqc7p5d8UVV2Q9LXXIkCFx3XXXxTHHHBPNmzfP2nf79u0xb968mDVrVvzud7+r71ABAAAAGgU1SDXIqqhBqkECAAAA1IYapBpkVdQg1SABoC5ZFA4AQL3p379/tG3bNjZs2JDZtmjRogJGVLHly5dH9+7d48knn4yBAweW+363bt2iW7duWdv233//mDdvXpXFuJYtW8a//Mu/xLhx4+L888+PO++8MyIili1bFvfcc09ccMEF5foMHz68wmN17Ngxjj766FxPq9peeOGFmDx5cta2q6++OiZNmlRu306dOsXll18eRx55ZBx55JGxfv36iIhYuHBhTJw4MW655Zacxly7dm1ERAwbNiz+/Oc/x1577VVunwMOOCBmzJgRY8eOjT//+c8R8WlB+c477ywXbyGtW7cuHnvssUx74MCB8dxzz0WrVq0q3L9Zs2YxdOjQGDp0aFx11VXxxhtv1FeoAAAAAI2GGqQaZFXUINUgAQAAAGpDDVINsipqkGqQAFCXSgsdAAAAxaOkpCQ6d+6cte2DDz4oUDSVmzp1aoWF0D3p2rVrtZ7OWFpaGrfeemv07ds3s+2uu+6qVox1bfLkyZEkSaY9duzYCguhuxs+fHjccccdWdvuvPPOWLduXc7jtm/fPv74xz9WWAjdpUmTJuUKn7Nmzcp5jPqwePHi+OSTTzLts846a4+F0IpUZ/4BAAAA8Ck1yM+oQe6ZGuSn1CABAAAAqk8N8jNqkHumBvkpNUgAyD+LwgEAqFcdOnTIau/+tMy0+OIXvxjHHXdcnY/TvHnzOOWUUzLtl156KTZv3lzn4+Zi7dq1cf/992faJSUlcdNNN+XU95vf/GaMHDky0964cWNMmzYt57EnTJgQPXv2rHK/gQMHxqBBgzLtBQsWpGo+lf2/bNasWYEiAQAAACguapCfUYOsmBokAAAAALWhBvkZNciKqUECAHXFonAAAOpV27Zts9rbtm0rUCR79q1vfavexurdu3fm35988knMmzev3sauzPPPP5/1f/PFL34x+vfvn3P/c845J6v99NNP59z3m9/8Zs77DhkyJPPvnTt3xvvvv59z37rWo0ePrPZ9990X27dvL1A0AAAAAMVDDTKbGmR5apAAAAAA1IYaZDY1yPLUIAGAumJROAAA9erjjz/Oardo0aJAkezZiBEjatV/06ZN8bvf/S7OP//8GDlyZPTo0SPatWsXpaWlUVJSkvV1/vnnZ/VdtWpVrcbOl7/+9a9Z7SOPPLJa/Y866qis9l/+8pec+jVr1iwGDx6c8zhdu3bNaq9bty7nvnWtZ8+eccABB2Taf/3rX+MrX/lKPPfccwWMCgAAAKDxU4NUg6yMGiQAAAAAtaUGqQZZGTVIAKAuNS10AAAAFJeyxaqyT8xMg92fWlkd27dvj5tvvjl+9rOflSv65mrt2rU16pdvS5cuzWoPGjSoWv379OkT7dq1y7wO7777biRJEiUlJZX269SpUzRp0iTncdq0aZPV3rx5c7XirGvXXnttfPvb3860n3jiiXjiiSeiV69ecdxxx8Xo0aPjC1/4QvTs2bOAUQIAAAA0LmqQlVODVIMEAAAAoHbUICunBqkGCQDUHZ8UDgBAvUmSpNwTIHv06FGgaPasffv21e6zefPm+MpXvhJXXnlljQuhERFbt26tcd98WrNmTVa7S5cu1T5G586dM//esWNHTq9Ly5Ytqz3O7pIkqVX/fDvttNPipz/9abki8JIlS+L222+P0047LXr16hW9evWK8847L5544onUnQMAAABAQ6IGWTU1SDXItJ0DAAAAQEOiBlk1NUg1yLSdAwA0Jj4pHACAevPGG2/Exo0bs7b17du3QNHsWbNmzard58ILL4wnnngia9tee+0VY8aMicGDB8d+++0X7du3j1atWmU9AfKxxx6LG264odYx59uGDRuy2mWfRJmLsn0+/vjjGhWaG7qJEyfGMcccEz/5yU/i0UcfjR07dpTbZ+nSpTFlypSYMmVKHHzwwXHzzTfHMcccU4BoAQAAABo2NUg1SDVINUgAAACAuqQGqQapBqkGCQCFZFE4AAD15m9/+1u5bUOHDi1AJPn18ssvx913351pN2vWLH7xi1/EhRdeGM2bN6+078KFC+s6vBpp27ZtVrtsETsXZfu0a9euVjE1ZIcddljMnDkzPvjgg3jsscdizpw58fTTT8eiRYvK7Ttv3rw47rjj4qabboqLL764ANECAAAANFxqkOWpQRYHNUgAAACA+qEGWZ4aZHFQgwSAdCgtdAAAABSP6dOnZ7X79esX++67b4X7lpSU1HicTZs21bhvTdx3332RJEmmPWnSpPjhD39YZSE0IuKjjz6qy9BqrGPHjlnt1atXV/sYu/dp0qRJURdDd9l7773jzDPPjLvuuisWLlwY77//ftxzzz3x9a9/PevJrEmSxKWXXhp/+ctfChgtAAAAQMOjBlmeGmRxUYMEAAAAqFtqkOWpQRYXNUgAKCyLwgEAqBeLFi2KRx55JGvbSSedtMf9W7ZsmdXevHlzzmOtXLmyesHV0u4Fq9LS0pgwYULOfV977bW6CKnWevbsmdV+5ZVXqtV/0aJF8fHHH2fa+++/f60K3I1Vjx494vTTT4/p06fHggUL4tBDD818L0mSmDx5cgGjAwAAAGhY1CArpgZZ3NQgAQAAAPJHDbJiapDFTQ0SAOqXReEAANSLyy67LHbu3Jlpl5aWxnnnnbfH/du3b5/VXr58ec5jvfDCC9UPsBZ2j22vvfYq93TJPdm5c2c89dRT1Rpr94Li7k/lzLeRI0dmtZ944olq9S+7f9njUV7Pnj1j2rRpWdvmzp1boGgAAAAAGh41yPLUINmdGiQAAABA7ahBlqcGye7UIAGg7lkUDgBAnZs8eXI88MADWdvGjx8f/fr122Ofsk9ofOmll3Ie7/e//331Aqyl3YuS27Zty7nfQw89FO+99161xmrTpk3m35s2bapW3+oYOXJkNG/ePNOeO3duvP322zn3//Wvf53VHj16dN5ia8z69esX3bp1y7RXrVpVwGgAAAAAGg41yIqpQVKWGiQAAABAzahBVkwNkrLUIAGgblkUDgBAnfnkk0/i0ksvjUsuuSRre/fu3eP666+vtO+AAQOidevWmfbjjz8ea9eurXLMF154oVzhta5179498+81a9bE66+/XmWfDRs2xKWXXlrtsTp16pT595IlS6rdP1cdOnSIk08+OdNOkiQuu+yynPpOnz49nn/++Uy7bdu28a1vfSvvMTZG27Zti/Xr12fauT5tFQAAAKBYqUHumRokFVGDBAAAAKgeNcg9U4OkImqQAFC3LAoHACDvtmzZElOmTIlBgwbFzTffnPW91q1bx/Tp06Nr166VHqNJkyZx3HHHZdqbN2+OK664otI+CxcujG984xuxY8eOmgdfA1/4whey2ldccUXs3Llzj/tv2rQpvva1r8WiRYuqPdZBBx2U+feqVatizpw51T5Gri6++OIoLf3sLcOMGTPiuuuuq7TPyy+/HOeee27WtnPPPTfat29fJzGm2bRp0+I//uM/Ys2aNTn3ufXWW2Pz5s2Z9vDhw+siNAAAAIAGTw1SDXJ3apBqkAAAAAD5pgapBrk7NUg1SABIC4vCAQDI2d///veYPXt21tesWbPit7/9bfzqV7+Kf/u3f4vRo0dH586d47zzzov58+dn9e/WrVs8+uijMWrUqJzG+9d//des9pQpU+Kcc86JZcuWZW3/6KOP4pZbbokRI0bEkiVLom/fvrU70Wo6/fTTs4qGM2fOjHHjxpV7UuaWLVti+vTpMXjw4Hj88ccjIuKf/umfqjXWsccem9U+6aST4sorr4w//OEP8dhjj2X939Sk2Lq7z3/+83HxxRdnbfvxj38cJ598csybNy9r+5o1a+LGG2+MUaNGxbp16zLb+/btW2UBtbFasWJFXHXVVbHvvvvGySefHL/97W9j6dKlFe771ltvxfe+971yT00tmwMAAAAAjZ0aZMXUINUgK6IGCQAAAFB9apAVU4NUg6yIGiQApE/TQgcAAEDDcdlll9W476mnnhqTJ0+O7t2759znn//5n2Ps2LHx8MMPZ7bdddddMXXq1DjggAOiQ4cO8dFHH8WiRYsyT6Rs06ZN3HffffX6ZMGBAwfGhAkT4rbbbstse+SRR+KRRx6J/fbbL/bee+/YsGFDLFmyJDZt2pTZ50tf+lKcccYZ1Sp4jR8/Pn72s5/FqlWrIiJi7dq1cf3111e47zXXXBPXXnttzU7q//vZz34Wr7zySsyePTuz7f7774/7778/evToET169IiPP/44Fi1aFNu3b8/q27lz57jvvvuiTZs2tYqhodu0aVPmNYuI6NChQ3Tv3j06dOgQ27Zti3fffTdWrlxZrt+pp54aJ554Yj1HCwAAAFBYapAVU4NUg6yMGiQAAABA7tQgK6YGqQZZGTVIAEgPi8IBAKgznTp1iq9//evx/e9/Pw4++OAaHePuu++Or3zlK/HCCy9ktiVJEm+99VaF4z3wwAMxbNiwGsdcU5MnT4533nknq3AbEfHuu+/Gu+++W27/L3/5y/HHP/4xHnzwwWqN06lTp7j//vvjlFNOiRUrVtQm5Jy0aNEiZs6cGd/5znfi3nvvzfresmXLyj2tdJcDDjggHnrooRg4cGCdx9jQrF27NtauXVvpPv/6r/+aVVwHAAAAoGJqkGqQapDlqUECAAAA5I8apBqkGmR5apAAUDilhQ4AAICGrXnz5tG+ffvo3bt3HH744TF+/Pj4xS9+Ec8++2x8+OGHcccdd9S4EBrxafHvySefjIkTJ0bbtm0r3Kdp06Zx+umnx//8z//El770pRqPVRvNmzePGTNmVPkU0F69esUvf/nLmD17dnTo0KFGY33pS1+KN954I375y1/GuHHjonfv3tGuXbsoLa2bX++bN28e99xzT8yZMyeOPPLIaNp0z8+W6tu3b9x0000xb968oi+Enn/++TFjxow499xzo1+/flXu36JFizjppJPimWeeiTvuuKPS1xkAAACgmKhBfkoN8lNqkJ9RgwQAAADIDzXIT6lBfkoN8jNqkACQPiVJkiSFDgIAAHKxbdu2eOaZZ2LBggWxevXqaNmyZfTt2zdGjx4dHTt2LHR4GZ988km88MIL8eqrr8bq1aujSZMm0b179xgyZEgMHjy40OHV2tq1a2Pu3LmxbNmyWL16dbRp0ya6desWQ4YMiQEDBhQ6vLyaOnVqnH322Zn2XXfdFWeddVaNjrVy5cp4/fXXY9GiRfHRRx/Fpk2bonXr1tGxY8cYOHBgDB48ONq0aVPjWJcsWRK9e/fOtM8888yYOnVqjY8HAAAAUIzUINNBDfKsGh1LDRIAAAAg/dQg00EN8qwaHUsNEgAKzyNXAABoMJo3bx5HHXVUHHXUUYUOpVJNmzaNww8/PA4//PBCh1InOnToEGPHji10GA3OXnvtFaNHj47Ro0cXOhQAAAAA9kANMh3UIGtGDRIAAAAg/dQg00ENsmbUIAGg8EoLHQAAAEBDcfbZZ0dJSUnW15w5cwoSS9k4dn86JgAAAADQMKlBAgAAAAB1SQ0SABo2i8IBAAAAAAAAAAAAAAAAAABSzKJwAAAAAAAAAAAAAAAAAACAFCtJkiQpdBAAAABp9MEHH8Rrr71W6T7Dhw+Pjh071lNEn5k9e3al3+/Ro0cceOCB9RQNAAAAAFATapAAAAAAQF1SgwSAxsWicAAAAAAAAAAAAAAAAAAAgBQrLXQAAAAAAAAAAAAAAAAAAAAA7JlF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECKWRQOAAAAAAAAAAAAAAAAAACQYhaFAwAAAAAAAAAAAAAAAAAApJhF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECKWRQOAAAAAAAAAAAAAAAAAACQYhaFAwAAAAAAAAAAAAAAAAAApJhF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECKWRQOAAAAAAAAAAAAAAAAAACQYhaFAwAAAAAAAAAAAAAAAAAApJhF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECKWRQOAAAAAAAAAAAAAAAAAACQYhaFAwAAAAAAAAAAAAAAAAAApJhF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECKWRQOAAAAAAAAAAAAAAAAAACQYhaFAwAAAAAAAAAAAAAAAAAApJhF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECKWRQOAAAAAAAAAAAAAAAAAACQYhaFAwAAAAAAAAAAAAAAAAAApJhF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECKWRQOAAAAAAAAAAAAAAAAAACQYhaFAwAAAAAAAAAAAAAAAAAApJhF4QAAAAAAAAAAAAAAAAAAAClmUTgAAAAAAAAAAAAAAAAAAECK/T81tHjZVqgQ+QAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAD2sAAAnqCAYAAACjMwpkAAAAOnRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjEwLjMsIGh0dHBzOi8vbWF0cGxvdGxpYi5vcmcvZiW1igAAAAlwSFlzAAAuIwAALiMBeKU/dgABAABJREFUeJzs3Xe0VNX5OO730ntvggiCKGAFQewCKjY0gjVWVFSM3VRjPrbEkmhMjEZssQYTu4garKgoAiIKioigINJ7lc78/vAHX+bO3Htn5jbA51nrruVszt77nZkz++xzPO/ZeYlEIhEAAAAAAAAAAAAAAAAAAABkpUJ5BwAAAAAAAAAAAAAAAAAAALAtkqwNAAAAAAAAAAAAAAAAAACQA8naAAAAAAAAAAAAAAAAAAAAOZCsDQAAAAAAAAAAAAAAAAAAkAPJ2gAAAAAAAAAAAAAAAAAAADmQrA0AAAAAAAAAAAAAAAAAAJADydoAAAAAAAAAAAAAAAAAAAA5kKwNAAAAAAAAAAAAAAAAAACQA8naAAAAAAAAAAAAAAAAAAAAOZCsDQAAAAAAAAAAAAAAAAAAkAPJ2gAAAAAAAAAAAAAAAAAAADmQrA0AAAAAAAAAAAAAAAAAAJADydoAAAAAAAAAAAAAAAAAAAA5kKwNAAAAAAAAAAAAAAAAAACQA8naAAAAAAAAAAAAAAAAAAAAOZCsDQAAAAAAAAAAAAAAAAAAkAPJ2gAAAAAAAAAAAAAAAAAAADmQrA0AAAAAAAAAAAAAAAAAAJADydoAAAAAAAAAAAAAAAAAAAA5kKwNAAAAAAAAAAAAAAAAAACQA8naAAAAAAAAAAAAAAAAAAAAOZCsDQAAAAAAAAAAAAAAAAAAkAPJ2gAAAAAAAAAAAAAAAAAAADmQrA0AAAAAAAAAAAAAAAAAAJADydoAAAAAAAAAAAAAAAAAAAA5kKwNAAAAAAAAAAAAAAAAAACQA8naAAAAAAAAAAAAAAAAAAAAOZCsDQAAAAAAAAAAAAAAAAAAkAPJ2gAAAAAAAAAAAAAAAAAAADmQrA0AAAAAwDbp3Xffjby8vKS/d999t7zDArYR+cePG2+8sbxDAgAgB+Z1QElavXp1PPbYY3HWWWdFhw4dolGjRlGpUqWkcaZevXpJdXK9RrWtXtvq3r17Uszdu3cv75AgrdatWyftq/369SvvkAAAAIDtWKXyDgAAAACAzK1duzYmTZoUEydOjAULFsTSpUujcuXKUb9+/WjcuHHsu+++0aJFi/IOEwAAAAAAtikvvfRSXHTRRTF//vzyDgUAAAAA2MZI1gYAAAAowLRp02LnnXculbbr1q0bS5YsKXK7devWxbvvvhtvv/12DBs2LMaOHRvr168vtM6OO+4Yp5xySlxyySXRrl27nGPs3r17vPfeeznXL8yLL74YJ554Yqm0HfHjiiQ9evRIKjv33HPjscceK7U+YXvXr1+/ePzxx5PKhg0bViIr56Qbb6ZOnRqtW7cudtsAAAAAUJQnn3wyzjnnnPIOAwAAAADYRlUo7wAAAAAASDV+/Pi44IILomnTptGrV6/485//HKNHjy4yUTsiYsaMGfG3v/0tdtttt+jfv38sW7asDCKmvOTl5SX93XjjjeUdEvD/e/fdd1N+o++++255hwWwTZo2bVrKmOpBPGzvzPUBoGy0bt066Zjbr1+/8g5pm9W9e/ekz7IkHvJXFmbOnBkDBgxI+28tWrSIPffcM/bee+/Nf3vuuWcZR8iWzJMBAAAA2BpZWRsAAABgK/TCCy/EI488Uqw2EolE/Otf/4o333wz3nzzzdh1111LKDoAAAAAANg+3HffffHDDz8klZ1//vlx8803R4sWLcopKgAAAABgWyJZGwAAACALNWvWjF122aXY7dSuXTunelWrVo2uXbvGgQceGM2bN48mTZrEhg0bYvbs2TFixIj43//+F2vWrEmqM3369OjZs2cMHz48dt5552LF3aFDh6hSpUqx2oiIqFu3brHbAAAAAACA4nrppZeSXu+3337x8MMPR15eXvkEBAAAAABscyRrAwAAAGShS5cu8e6775Zpn5UqVYpjjz02zjvvvDj66KOjWrVqBW47e/bs+PWvfx2DBg1KKp85c2acf/75MWzYsGLF8tprr0Xr1q2L1QZASenevXskEonyDgPYRhk/AAAAWL58eXz11VdJZaeeemqZJGq7tgUAAAAA248K5R0AAAAAAOlVr149rr766vj+++9j8ODBceKJJxaaqB0RscMOO8S///3vuPnmm1P+7d13343nn3++tMIFAAAAAIBtyowZM2Ljxo1JZbvttls5RQMAAAAAbKskawMAAABshY4++uj49ttv46677opmzZplXf///u//onfv3inlTzzxREmEBwAAAAAA27ylS5emlNWsWbMcIgEAAAAAtmWStQEAAAC2Qvvvv39OSdpbuummm1LK3njjjVi7dm2x2gUAAAAAgO3B6tWrU8ry8vLKIRIAAAAAYFtWqbwDAAAAAKB0dO7cOZo1axZz5szZXLZ69eqYPXt2tGrVqhwj+2lYu3ZtTJkyJb766quYM2dOLFu2LCIiGjRoEA0aNIg999wzdtttt3KOMjs//PBDjBo1KubMmRPz58+PlStXRsOGDaNx48axzz77xM4771zqMSxdujRGjhwZkydPjqVLl0atWrWicePG0blz52jfvn2p9Tt58uSYOHFiLFiwIBYsWBAbN26M2rVrR/PmzaN9+/ax6667RsWKFUutf0rf3LlzY9y4cfHdd9/FsmXLYtWqVVGtWrWoUaNGNGvWLFq3bh277rpr1KpVq7xDTWvT73PWrFkxf/78WL16dTRu3DiaNGkSnTp1ih133LFU+p03b97mfhcsWBA1atSInXbaKfbdd99o3bp1qfRZkA0bNsRnn30WX375ZcydOzdWr14dNWvWjL322isOP/zwjOp/++238dVXX8XMmTNj2bJlsWHDhqhfv37Ur18/2rdvH3vuuWdUqFA2z8H9/PPPY9y4cTFnzpxYs2ZN1K9fP/bYY4/o1q1bVK1aNaM21q9fH5988kl88cUXsWDBgqhQoUI0bdo09tlnn9hrr71K+R38tG3cuDHGjh0bn3/+ecybNy/y8vKiUaNG0aZNmzjwwAOjSpUqpdr/rFmz4uOPP46pU6fGypUro0GDBtG8efPo2rVrNG/evFT7JjNr166N0aNHx4wZM2LevHmb51VNmjSJ3XffPdq1a1cmcXz55Zfx2WefxezZs2Pt2rXRpEmT2HHHHeOggw4qtWPehg0bYuzYsfHdd9/F/PnzY/HixVGnTp1o3LhxtGvXLjp16lTqyTFr166NMWPGxKRJk2LBggWxZs2aqF27duy///7RrVu3jOpvT3P9Td/J1KlTY/78+bF06dJo0KBBNG7cOHbdddfYc889yySOefPmxZgxY2Lq1KmxdOnSzWNnnz59olGjRmUSQ6YSiURMmDAhJk+eHAsXLowFCxZEXl5e1KlTJ1q2bBkdOnSINm3alMi+XF7zvPy29bnJunXrYvTo0fHll1/GwoULIyKiadOm0blz59h7770zbmfZsmXx8ccfx6RJk2LJkiVRs2bNaNasWRx00EEl+l0kEon47rvv4quvvorp06fHsmXLYu3atVGvXr2oX79+tG3bNjp37hyVKpXNbT/ff/99fPzxx/Hdd9/FDz/8EA0aNIimTZvGQQcdFE2bNi3x/r755psYN27c5nl5nTp1om3bttGtW7do2LBhife3ybZ+XliaEolEfP755zF58uSYP39+LFq0KOrWrRtNmjSJnXfeOTp37lxm50rbi9WrV8eoUaPiq6++isWLF0flypWjefPmseuuu0bnzp0lC5OTjRs3xscffxzffPNNzJ49O9atWxcNGjSI9u3bZ3XMLinz58+PkSNHxrfffhsrVqzYPG5069bN/6PYwqbzkxkzZsTChQtj8eLFUbVq1c3Hv44dOxb74b7pTJ48OcaOHRszZsyI1atXR506daJDhw5xwAEHZLy6fCKRiHHjxsW4ceNi3rx5sWHDhmjatGl07Ngx9ttvvxIfy2bOnBljxoyJWbNmxaJFi6JmzZqx8847u94BAAAAbB0SAAAAAKQ1derUREQk/R122GHlHVZWunbtmvIeRo4cmVHdww47LKXu1KlTSzfgEjJs2LCU2M8999xS7/fTTz9N3HDDDYlDDz00UbVq1ZQY8v81btw4cd555yW+/PLLjPtI996y/WvVqlXG/a1bty7x0EMPJXr27JmoUqVKoe22bds2ce211yYWLlyY9Wd37rnnFhrjp59+mjjppJMSlStXLvR93XPPPYm1a9dm3X86n332WeL8889PtGzZssjPtF69eom+ffsm/vvf/ybWrFmT0tbbb7+dUueGG24odox77713UptNmjRJ239JyP8dRURi2LBhJdJ2ruNNut9DNjEtXrw4ccsttyQ6duyY0W+nYsWKib333jtx1VVXJT744IPExo0bU9q84YYbiv0bzWa8euaZZxJHHnlkkWPO7rvvnrjhhhsSS5cuzbjtwgwePDhx2GGHJSpUqFBgn/vss0/iiSeeSPqc8n/XmRxXi/qev/vuu8Sll16aqF+/fto4Cutj0qRJidtuuy3Rq1evRM2aNYv8burWrZs4+eSTMz6WplPYWLBq1arE7bffXui407Bhw8T111+f+OGHHwrsY+7cuYlrrrkm0bBhwwLb2XnnnROPPvpo2v34pyKXcbmo/XHp0qWJ66+/PtG0adMCP/uaNWsm+vXrl5g+fXrWMRd1vHzxxRcTBxxwQIF9V6hQIXHIIYckXnjhhaz7Tjc3fvTRR7NuJ5HIfCx49NFHiz2mbm3z9zfffDNxwgknJGrVqlVo3G3atElcc801idmzZ+fUT6tWrQo8tqxZsyZx1113JXbeeecC+69evXripJNOSowbN66E3vmP7/3kk09O1KtXr9D33rBhw8Q555yTmDhxYtZ9pNtntpxTfPHFF4lzzjmnwDG/sGPw9jjX//jjjxOnn356gcfQTX/NmzdPXHjhhYkpU6Zk3PaWCvvNb9y4MTFo0KDE/vvvn8jLy0vbf0nNOUvCe++9lzj99NMTTZo0KfK7aNq0aeLMM89MvPrqq4kNGzZk3VdZzfPyt7etzU2KOjbPnDkz8Ytf/CJRu3btAvveddddE0888USh/YwbNy5xyimnFPp9HHDAAYkPPvggq/i39P333yfuvvvuxAknnFDk7zIiEjVq1Egcc8wxiddffz3nPgs7XiQSicQLL7yQ2H///QuMIS8vL7HffvslXnvttZxj2GTjxo2Jhx9+ONG5c+cC+6tYsWLiqKOOSrz//vtJdQvbj4tSGueF25NJkyYlLrjggkSzZs0K/VwaNmyYOOOMMxJjx47NqZ+i9sVMpTsnTyfd3DaXv3SKGpe++eabxHnnnZeoUaNGge3utNNOieuuuy6xYsWKrD+DXM670ylqXrWlkvgsy/K6c3Gv3aT7THO9RlXca1ubLFiwIHHllVcW+lutVatW4sILL0z6rHPtv6j9bNiwYYkjjzyy0OtGHTt2TPz73//OaBwt63lyWVi/fn3iiSeeSBx11FGFjgeb/nbbbbfElVdemdE4W9iYun79+sT999+faN++faH7yuWXX17odf5ly5YlbrrppkSLFi0KbKdp06aJO++8M7Fu3bpif14vvPBC4pBDDinwnCEvLy9x4IEHJgYPHpzxZwEAAABQ0iRrAwAAABRge0jW3n333VPeQ6YJF5K1Mzdx4sTErrvumvONYnl5eYn+/fsnVq9endN7K60b01588cXELrvsknX7derUSdx7771ZfYYFJZ9t3Lgx8Yc//CFRsWLFjPvv1KlTYu7cuVn1v6Vvv/02ceKJJxZ441dRf3vuuWfadjt06JC0XYsWLRLr16/POc4RI0ak9H3ttdfm3F5Rtrdk7WeeeSbRuHHjYv2W0iWRlVWy9tixY9M+kKOov0aNGiXuv//+jD6jdBYsWJD42c9+llWf3bt3T8yfPz+RSJR8svbDDz9c5A2t6fpYsGBBolOnTsX6nn72s58lFi9enPVnmL+dTYkkX375ZVbHkt133z3x3XffpbQ/ePDgRIMGDTJu5/jjjy+1hzxs7Qr6LgpT2P74/vvvF3qTcv6/6tWrp9xEXJSCjpcrV65M9O3bN+t9eNNvMxOStYvnm2++SfTq1Svr+GvWrJm4+eabs070LOiG9ClTpqQ9Ryjor1KlSolrr702p0TTTcaPH5/o2bNn1u+9YsWKiYsvvjijOfImhSUV/fGPf0xUqlSp0D7THYO3x7n+/PnzE6eddlrW893KlSsnrrjiiqy+k0Si4N/8nDlzEoceemiR/W4NydqfffZZonv37jl/L8cff3zGfZX1PC9/O9va3KSwY/Pzzz+fqFu3bsZ9n3LKKSn798aNGxM33XRTxuekeXl5iVtuuSXr7+Hggw/O+Rw0IhIHHnhg4vvvv8+634KOF0uWLEkcf/zxWcVw7rnn5pyM9e233yYOPvjgrPq7/PLLN59TF7QfF6W0zgu3BytXrkxccsklRR470/0GzjrrrMSiRYuy6u+nkqz9yCOPJKpXr55x+zvttFPirbfeyuozkKxdtO0tWfu///1voQ9Eyf9Xs2bNxGOPPVas/gvaz1avXp3o379/Vp9nr169inwwwfaWrP3cc8/ldN19099f//rXQtsvaEydOXNmolu3bhn3s+OOO6b9/0kffvhhYqeddsq4nW7duuV0DS2R+PHcJdtrkaecckpi5cqVhX4WAAAAAKWhQgAAAACwXdqwYUNMnTo1pXyHHXYoh2i2b3PmzImvv/465/qJRCIefvjhOPTQQ2PZsmUlGFnu8dxwww3Rp0+fmDJlStb1ly1bFpdddllcfPHFsWHDhpzj2LhxY5x99tnxpz/9Kat2Pv300zj00ENjxYoVWfc5bNiw6Nq1a7z00kuRSCSyrh8RBX6Hl156adLrmTNnxssvv5xTHxERAwcOTHpdoUKFuOiii3Ju76fk4YcfjtNOOy3mz59f3qHkZOjQoXHIIYfExx9/nHXdBQsWxIABA+LKK6+MjRs3Zl23Z8+eMXjw4Kzqvfvuu3HooYfG4sWLs6pXlDvuuCP69+8fP/zwQ9Z1ly9fHp9++mmx+h88eHDst99+MWPGjGK1ExHxxRdfxEEHHZTVsWTChAlx1FFHJY05jz32WPTp0ycWLVqUcTtDhgyJM844I6t4SfXKK6/EEUccETNnzsy4zqpVq+Kkk06KoUOHFqvvNWvWxNFHHx0vvPBCVvUGDx4chx9+eCxcuLBY/VO0Tz75JA488MB44403sq67cuXKuP766+O0006LNWvWFCuOqVOnxkEHHRQTJkzIuM769evjtttui379+mV93Ij4cYw54IAD4p133sm67oYNG+KBBx6I7t27x7x587Kuv6VLL700/u///i/Wr1+fdd3tba7/7bffxoEHHhhPP/101vPddevWxT/+8Y848sgji31cnzNnThx44IHx/vvvF6udsvD000/HgQceGO+++27ObWT63ZfXPC+/7WFu8u9//ztOPvnkWLp0acZ1nn322Tj//PM3v04kEnHhhRfGDTfckPE5aSKRiOuuuy7uvfferOL94IMPcj4HjYgYMWJEdOnSJcaNG5dzG5ssXLgwDj744BgyZEhW9R5//PHo169f1v19++23ceihh8YHH3yQVb177rknzj777Jw/t239vLA0bTr3GzhwYNbHzkQiEf/+97/j4IMPjunTp5dShNumgQMHxvnnnx+rVq3KuM706dPj2GOPjVdffbUUI2Nb9sADD8TPf/7zrM7rVq5cGf369Yv777+/RGNZvXp1HHPMMfHwww9nVe+NN96IY489tljXkbcVGzdujF//+tdx8skn53TdfZNczitmzZoVBx54YIwaNSrjOjNmzIhevXrF999/v7nsjTfeiCOOOCKrMX7UqFFx9NFHZ31MWbhwYRx++OFZX4t89tln45hjjom1a9dmVQ8AAACguCqVdwAAAAAAlI7//e9/KQlsrVq1isaNG5dTRD8d9evXj65du0aHDh2ibdu2UadOnahVq1asWrUqFixYEBMmTIg33ngj5Yam0aNHx4UXXhhPP/10gW3XqlUr9t57782v89+I3bRp02jWrFmh8TVv3rzQf7/kkkvigQceSClv0KBBHHnkkbHvvvtGkyZNokaNGrFkyZKYMGFCDB06NCZNmpS0/YMPPhj16tWLP//5z4X2V5DrrrsuBg0atPl1y5Yt47jjjos999wzGjVqFCtWrIiJEyfG888/n/JggkmTJsXvfve7rG6Qf/XVV+PEE09Me9NYo0aN4ogjjoguXbpE48aNo1q1arFkyZKYPn16jBkzJkaMGBHLly8vtP1zzjknrr322qTtBg4cGH369Mk4xk0WLlwYzz77bFLZMcccE61bt866rZ+aSZMmxWWXXZZyQ3/16tWjZ8+e0bVr12jVqlXUqlUr1q9fH8uWLYvZs2fHhAkT4uOPP45p06YV2n6zZs02/0ZXrFgR33zzTdK/t23bNmrVqlVoGzvttFOB/zZs2LA4/vjj0+6n++yzTxx//PHRunXrqF69esyePTvee++9eP3111MS/P7xj3/Ehg0bMv6NrF+/Po455pgYP358yr/tsMMOceKJJ8Yee+wRjRo1ikWLFsWkSZNi8ODBm3+bEydOjHPOOSejvjLxxhtvxO233775ddWqVaNHjx7RvXv3aNasWVSqVClmzJgRo0aNyujBDbVq1do8brdr1y7q1q0btWvXjrVr18bixYvjyy+/jGHDhsXEiROT6k2ePDlOO+20eO+996JSpdz+l8vSpUujd+/em5PeKleuHD179oyePXtG8+bNo0KFCjFt2rR4+eWXU26o/eqrr+Laa6+Nf/7zn/Huu+/GhRdeuDk5q27dunHMMcfEAQccEE2aNIk1a9bExIkT4+mnn07Zj59//vl45pln4tRTT83pPfzUffbZZ3Httdduvgm4evXqcfjhh8ehhx66eX/8/vvv44033oi33347qe769eujf//+MWHChKhbt25O/f/yl7+M4cOHb37dqFGj6Nu3b+y1117RqFGjWLBgQXz++efxwgsvpCQjjR8/Po466qj46KOPonLlyjn1X5oaNGiweUxdu3Ztym+wZcuW0aBBg0Lb2GWXXUotvkxMnDgxunfvnnYsateuXfTp0yd22WWXqFOnTsyZMydGjx4dL7/8csr2zz33XKxevTrrxLlN1q1bF3379o25c+duLtt1112jb9++m49Nc+bMieHDh8drr70Wq1evTqr/5JNPRv369ePuu+/OuM+nnnoqzj777JSk0SpVqkTPnj2jW7du0bJly6hbt26sWLEipk2bFm+//XZKst7IkSOjb9++MWzYsJz204ceeijuu+++za9r1aoVRx55ZBx00EHRtGnTSCQS8f3338ewYcOiYsWKRba3Lc/1582bFwcffHDMnj075d923HHH6Nu3b3To0CEaNGgQ8+bNi3HjxsWLL76YkvwzfPjwOOKII2LEiBFRtWrVQuNJZ+PGjXHqqafGt99+u7msTZs2cdxxx0X79u2jUaNGsXDhwpg6dWo8//zzWbdfkh544IEYMGBA2n9r0aJF9OrVK/bcc89o3LhxVK5cORYvXhzffvttjBkzJj766KOU31Jhymuel9/2MDcZM2ZM/P73v988569Xr14ce+yxsf/++0eTJk1i1apVMXHixHjmmWdS+n7qqafixBNPjFNOOSVuvfXW+Ne//rX531q1ahW9e/eOPfbYIxo2bBhLliyJ0aNHxzPPPJOSNPXb3/42evfundM5WtWqVaNLly7RsWPH2G233aJ+/fpRu3btWL9+fSxdujS++uqr+OCDD+KTTz5Jqjd37tw4+eST45NPPok6depk3W/Ej3OTE088Mb744ovNZZ06dYqjjjoq2rRpE/Xq1YtFixbFqFGj4oUXXkhJhh80aFCceOKJcfLJJ2fU3+LFi6NHjx5pH4C0yy67RN++fZOOkyNGjIhXX301Vq5cGRER//nPf2LffffN+n2W9nnhtmzVqlXRo0ePpH1gk0aNGkWfPn1ir732iiZNmsTChQs3X5eZNWtW0rZffvllHHzwwfHZZ58VOV8rD1WqVEk65n755Zexbt26za/r169f6Ll5tkaOHBl/+MMfNr+uVKlS9OzZM4444oho0aJFrFmzJr777rt4+eWXUx4stnbt2jjppJPi3Xffjf3337/EYipJW36WU6ZM2fwbjYioWbNmRnPyKlWqlEps6Wx57SYi++s35X2OscmLL74Yl1xyScpYVrFixTjkkEOiV69e0aJFi6hYsWLMmjUrhg0bFm+//fbmc9fLLrss/vSnP5VYPOeff34MGzZs8+vddtstjjnmmGjfvn00aNAgli5dGp9++mk8//zzSeclERHvv/9+/O1vf4tf/epXadsui2viZeHss8+Op556Ku2/7bHHHnHkkUdG27Zto1GjRrFu3bpYtGhRfPnll/Hxxx/Hp59+mvMDStatWxcnnnhifPfddxERkZeXF4ccckgceeSR0bJly6hatWrMmDEjhg4dmnLdYu7cuXHJJZfEK6+8EhMnToyTTz5580MnqlevHr169dp8/WPDhg3xzTffxHPPPZfykLBRo0bFXXfdFb/5zW8yjvmoo45Key2yRYsWcdJJJ20+d5k7d258+umn8dJLL22ew77//vvxy1/+MuvPCgAAAKBYyn4xbwAAAIBtw9SpUxMRkfR32GGHlXdYGTv++ONT4r/iiisyrn/YYYel1J86dWrpBVyChg0blhL7ueeeW6r9NWvWLPG73/0uMWrUqMSGDRuKrLNx48bEq6++mmjXrl1KrM8++2zGfeeve8MNNxTjnSQSjzzySEqbDRo0SDzwwAOJVatWFfp+XnjhhUSTJk1S6g8ZMqTIfs8999ykOlWqVEnk5eUlIiJRu3btxIMPPphYv3592rpr1qxJ/Pa3v03pt2LFiokZM2Zk9L4nT56cqFevXkobTZs2TQwcODCxbt26QuuvXr06MXjw4MSxxx6baN26dYHbXXbZZUnt5+XlJSZPnpxRjFu68847U2J95ZVXsm4nG/m/o4hIDBs2rETaznW8SfdbLyqmCy64IKXOWWedlZg3b15GsU6YMCFx0003JVq0aJGYOHFiicdXmAULFiRatGiR0uZOO+2U+N///ldgve+//z5x3HHHpdSLiMRLL72UUd833XRTSt3KlSsnbr311sTatWvT1tm4cWNi4MCBiVq1am2uU7169ayPq+k+x4oVK27+75NOOikxffr0AuunG7umTp2aqFevXuKyyy5LvPvuuwW+h/w+/PDDRJcuXVLiueOOOzKqn0ikjttVq1bd/N+HH3544uuvvy6w7mOPPZaoVKlSymfxxRdfJO0bV1xxRWLx4sVp21i9enXikksuSYlj1113zfg9bC9yOYam2x+rVau2+b/PPvvsxKxZswqt36BBg5Q2brvttoxizj8WV61adfPxskKFConf/va3BR6vV61alfjd736XqFChQkr/N954Y5F9p5sbP/rooxnFnV/+cT+TsaAk+y8rq1evTuy9995p51ZPPvlkgfUWLVqU6NevX9px++9//3tGfbdq1arA/bRevXqJxx57rMC6M2fOTPTu3Tul77y8vIyPY1988UWiRo0aSfUrVaqU+PWvf13kMffTTz9N7Lvvvin9/+pXvyqy30cffbTQY8aAAQMSCxYsKLB+ut/P9jLX37hxY+KYY45JabN69eqJu+66q8D39cMPPyR+85vfpB07rrrqqoz6zv+b3/I7adiwYeKJJ55IbNy4scC4V69enfP7Lo4RI0YkqlSpkvK+27Rpk/jvf/9bYMybLFu2LPHUU08lDjrooCLHufKc523rc5N0x+Yt38Pll19eaN+XXnppSv3ddtstMWrUqM37fY0aNRIDBw4s8Jx09uzZiQMPPDClnYsuuiij95BIJBI1atRInHvuuYmhQ4cmfvjhh4zqfPHFF4kjjzwypd9LL700434LO17suuuuibfffrvAuvPmzUscddRRKf23b98+4/7TnWfWrVs38a9//avAOvPnz0/8/Oc/TxrHsh0vy/K8cFtz8cUXpz2W/v73vy9wnrl+/frEX/7yl6Tf3qa/Pn36ZNRv/n0x1+t4N9xwQ0oMZdl/IlH0OcMBBxyQ+Oqrrwqs/9prr6U9JrRv3z6jY2Iuc+100s2rMrlWU1L9l6WSuH6Taxu51ps/f37a67Bdu3ZNjBs3rsB63377beKII44odAzNpP/83/OW+3izZs0Szz33XIF1ly9fnjjnnHNS+q1Xr17Gx8Bsx/2twR133JESd0Qkunfvnhg9enSR9WfMmJH429/+lmjTpk2R7zf/mLbl+NypU6fEmDFjCqw7dOjQRM2aNVPifP/99xOdOnXa/Pr0008v8PrHhg0bEn/605/SHuMz/Y7TjedVq1ZN3H777QXOyVasWJG48sorN2+fl5eXcmwqzf9PBAAAACBZGwAAAKAA23Ky9jvvvJMSe15eXqE3auUnWTtzK1euLDKZtyCLFi1Kuslp002bmSrJG9OmTp2aklSz6667Jr7//vuM25g+fXpixx13TGpj9913LzKRId0N2hE/JjN99tlnGfV94YUXptT/4x//mFHdbt26pdTdfffdC00ALUhhv5OJEyem9JNJ4tGWNm7cmNhll12S2mjVqlVGiUPFsb0kazdq1Chp+549exa5f6azbt26xJo1a0o8vsKk28d33nnnjH6jGzduTJx11lkp9Rs3blzkTZLTp09PSVSqVKlS4vnnn88o7vfffz/tTZ6ZHlfTfY6b/rJ5CMmW1qxZk/HNofmtWrUqcfTRRyfF0bJly4yPAwW9l1NPPTWjNm699daUulveoP3Pf/6zyDY2btyYNrHnww8/zOg9bC9yOYYWtj9meswZPnz45gTrTX+77LJLRnULOl5GRGLgwIEZtTFw4MCUupUrV05MmTKl0HqStbN3yy23pJ3bZDon//3vf59Sv2rVqhk9jCb/zfmb/mrXrp1RIsCGDRuSEuE2/bVr167IOceGDRsSe+yxR1K9mjVrJt55552M3nci8eM4nX+cqlKlSpHHvHRJRZv+/vrXv2bc/5a2l7n+oEGDUtqrVq1a4q233sqo/gMPPJBSPy8vL/Hxxx8XWTfdXC/ixwcjTZgwIef3VJrWrFmT2GmnndLOXQpK/C1MUXPb8prnJRLb/tyksGPz3XffXWT9RCKRNuF403uoVatWYuTIkUW2sWjRokTjxo2T2qhTp07Gc84lS5ZktF1+GzZsSJx//vkpY+6iRYsyql/Q8aJr166JhQsXFll/9erVKWN+RCSGDx9eZN333nsvpV6tWrUSH330UUaxX3HFFQV+90WNl2V5Xrgt+eCDD1I+ywoVKiSeeOKJjOq/8soricqVK6e0UVjS5ibbe7L2pr/u3bsX+jDETb755ptE8+bNU+rffPPNRdaVrJ29bTFZe8CAASn1DjnkkMTKlSuLrLtu3bpE3759C9xPc0nW3vTXpk2bxLRp04qsv3HjxrTH38IearWlbMf98vb5558nPbBo099VV12V9TXd9evXF3nNuqDj+6GHHppYvnx5kX089dRTBc6NIiLx61//OqNY+/fvn9LOoEGDiqw3ZcqUlONJpUqVEi+++GJG/d51110F7t+StQEAAIDSVCEAAAAAyNiYMWNin332KfbfpEmTSi3GpUuXxvnnn59SfuaZZ8Zee+1VrLaPPfbYYr/3O+64o1gxbI1q1KgRlSpVyqlu/fr144knnkgq++ijj+LLL78sidCycscdd8QPP/yw+XXNmjVj6NChseOOO2bcRsuWLeO///1vUtmECRNiyJAhOcX06KOPxt57753RtrfffntUq1Ytqez1118vst4bb7wRo0aNSipr1KhRvPnmm9GyZcvMg/3/tW7dusB/a9++fRx++OFJZY8++misWbMm4/bfeuutmDJlSlLZxRdfHBUqlP3l3v79+5fImDhmzJgyiXf58uWxYMGCpLILLrgg8vLysm6rUqVKUaVKlZIKrUgLFiyIJ598MqmsYsWK8cILL2T0G83Ly4tHH3009txzz6Ty+fPnp7Sb34MPPhhr165NKvvlL38Zffv2zSj2Qw45JG677baMts3GfvvtF3fddVdOdatUqRLVq1fPqW61atXi8ccfjxo1amwu+/777+ONN97Iqb2IiHbt2sUjjzyS0bHkmmuuifr16yeVzZs3LyIizj777PjFL35RZBt5eXnxxz/+MaX8f//7X4YRk1/fvn3jD3/4Q0bbHnzwwXHKKacklU2ZMiW++eabnPvv169fDBgwIKNtBwwYEP369UsqW7duXQwcODDn/km1bt26uPfee1PKH3vssYzn5LfcckscffTRSWVr1qyJf/7znznHdc8990TXrl2L3K5ChQrx2GOPxa677ppUPnny5HjttdcKrfv888/HF198kVT26KOPRo8ePTKOs0qVKvHss89Go0aNNpetXbs253H/pJNOimuuuSanutvLXD/dZ/eXv/wlZW5akIsuuihlnEkkEjl/JxERDz/8cHTs2DHn+qXpsccei+nTpyeV7brrrvHqq69GvXr1sm6vsHOE8pznFWR7mJucccYZccUVV2S0bbq+N72Hu+++O7p161ZkG/Xr149f/vKXSWXLli2LESNGZBRD3bp1M9ouvwoVKsQ///nPpHPXlStXxn/+85+c2ouIqFevXjz33HPRoEGDIretWrVq/OUvf0kpz+Rc/O67705btv/++2cU59///vc48MADM9p2S9vyeWFp+9vf/pZSdtVVV8XZZ5+dUf3jjjsu7e/pr3/9a7Fj2x40bNgwnnvuuZRrV+m0adMmBg0alFJ+3333xbp160ojPLYhy5YtSznG161bN5555pmkaxUFqVSpUjzxxBOx0047lWhclStXjmeeeSZatWpV5LZ5eXlp55GZHD+2Rbfeemts2LAhqeyMM86Iv/3tb1lf061YsWJO16wbNmwY//3vf6NWrVpFbvvzn/88ZZ6+aW502GGHxe23355RnzfddFPK+8tkfpdurLv22mvjxBNPzKjfq6++On7+859ntC0AAABASZKsDQAAAJCFlStXxrhx44r9t2rVqlKJL5FIxDnnnBPTpk1LKm/UqFHceeedxW5/4sSJxX7vM2fOLHYc25s99tgjOnfunFT2wQcflGkM8+fPj0cffTSp7Ne//nXsvPPOWbd10EEHpSR9vPjii1m3c9hhh8UJJ5yQ8fYNGjSIY489Nqnss88+i40bNxZa789//nNK2T333BM77LBDxn1n47LLLkt6vXDhwnjmmWcyrp8/ma5y5cpxwQUXlEhs2frmm29KZExcuXJlmcS7fPnylLKGDRuWSd/F9fDDD8fq1auTyi6++OLYZ599Mm6jUqVKcc8996SUp0sm3GTjxo3x8MMPJ5U1aNAgrr/++oz7jYi49NJLY7fddsuqTlHuuOOOqFixYom2makmTZqkJFAWZ9y+4YYbombNmhltW7Vq1ejdu3dKecWKFeNPf/pTxn1269YtJQFs7NixGdfn/6lQoULaJKXCnHXWWSlln3zySU79V69ePe2xrDB//vOfUx5YkO3DQyjc888/H7Nnz04qO/bYY+P444/Pqp177703Zax78MEHc0rS6dKlS5xzzjkZb1+lSpW0yVX3339/ofXy74/du3dPeUBBJurWrRtXXnllUlkuc8oKFSqUyLlQrraGuf7IkSNTxpg999wzLr300qzaue2221KScp977rmYO3du1jH16NEj7fFsa5FuXH/88cczPl5no7zmeYXZ1ucmFStWzOphQV27dk2bsLbbbrvFeeedl3E7J598ckpZWcyvqlWrljLOFmecufLKK7NK4OvVq1c0btw4qayoec3s2bPj5ZdfTirr3LlzVp93Xl5e2v2+KNvyeWFpmjlzZrz00ktJZU2aNImbb745q3auueaaaNeuXVLZRx995FwjIm688cas9rXu3bvHSSedlFQ2Z86cGDx4cEmHxjZm0KBBKdfSfve730WzZs0ybqNmzZpx6623lmhcZ5xxRuy7774Zb9+xY8eUeXKu58Vbs2nTpqVc+23cuHGZPzDt6quvzup6d/7xZ5Nbb7014wTz5s2bpzxYpajjwZo1a+Kxxx5Laefaa6/NqM9N/vrXv0bVqlWzqgMAAABQXJK1AQAAALYj1157bcrNrnl5efHII49E06ZNyykqMpH/RtaRI0eWaf+vvvpqykME+vfvn3N7xx13XNLrd999N+s2Lrzwwqzr7LfffkmvV6xYUegDApYtWxbvvfdeUlnr1q1zSijK1PHHH5+ywkxRSU+bzJo1K2WV8r59+0aTJk1KLL7tWYMGDVJWSyvrZKlcvfnmmyllmaxSmN9hhx0Wu+++e1LZ559/XmCS1cSJE2POnDlJZaeffnpGKzVtqUKFCikr+RZHu3bt4tBDDy2x9nKNYUu5jtu1a9eOU089Nas6nTp1Sik78sgjs14VK387kyZNyqo+P+rZs2e0bds2qzr5j1cRuX/+P/vZz7I+DjRp0iRlRapFixbF6NGjc4qBVCU1brdt2zaOOuqopLKFCxfmlPDUv3//rFcNPfbYY1OSJ99+++0Ck8WnTZuWkmBRknPKadOmxXfffZdVGz179ix0VeOyUN5z/XT748UXX5z1Kn716tVLWaFu3bp1Oc31y+thQ5mYMGFCfPPNN0llhxxySMar/WarvOZ5Bdke5iZHHHFE1n2nS44/77zzsho327ZtG3Xq1EkqK6v5VUmOM9mei1esWDElOa+o9/3mm2/G+vXrk8pyOU517tw5unTpklWdbfm8sDS98847Kau+nnPOOVk/pKJy5cpp96F0Y91PSbVq1TJeoXxLF110UUpZJqvSsn175513kl5XrFgxzj333KzbOemkk6JevXolFFXJXMv9+uuvSyqcrcarr76aMr4OGDAgZc5Q2rKdf6eb37Vv3z4l+Trbdor6jkeNGhWLFi1KKjvrrLNSHjhXlB122CHrh6UBAAAAFFel8g4AAAAAgJJx3333pV1V8fe//72bUsrBN998EyNHjozx48fHN998E8uWLYtly5bFmjVrIpFIpGw/ffr0Ql+XtvwJy61atYoWLVrk3F7+FbmnTZsWS5YsyeoGwMMOOyzrftMlyy1dujRatmyZdvvhw4en3Cx3xhlnlOpqvRUrVowBAwYkrQYyYsSIGD9+fOy1116F1n3ooYdSbmi/5JJLSiXO7VG1atVir732inHjxm0uu/POO6NTp07Rt2/fcoyscBs2bIhRo0YllbVv3z4lGSdTp5xySkyYMCGp7MMPP0z7GaRL8si/gn2mevfunfUqOAXp3r17ibSzpZkzZ27+LX799dexdOnSWLZsWaxatSrtuJ0/iT3XcXv//fePypUrZ1Un/wMfIn5MIstW/uTFJUuWZN0GuR2vmjZtGjVr1kxaDW3p0qU59Z8/6TpTffv2jf/85z9JZSNHjsxpXyLVhx9+mPS6Zs2acfTRR+fU1qmnnhqvvfZaSvvdunXLqp1c9pUKFSrEz372s/jnP/+5uWz16tXx2WefRdeuXVO2zz+njIg46KCDsu53k/xzyoiITz/9NO04WJAePXrk3H9BtrW5fv79MaLglfKKcuqpp8Z9992X0v5pp52WVTul8b2UlHTJ57kk2GWiPOd5Bdke5ia5PNSnpN5Dq1at4vPPP9/8Otf3sHDhwhg+fHh8/vnnMXHixFi8eHEsX748Vq5cmXacyZ/U9P333+fUb9u2bXO6FpD/XLyoeU2684xcz8n69u0bY8aMyXj7bfW8sLSlO1akWy0+E6eeemr85je/KbL9n5Lu3btH3bp1s653xBFHRJ06dWLZsmWby8r6oS9sffLvA506dcpqxeRNqlWrFocffng8//zzxY6pevXqaR9KVpT8x48NGzbEihUrolatWsWOaWtRlnPLgrRr1y6rldcjSm9+t379+kK/45KeIzz33HM51QUAAADIhWRtAAAAgCwcdthhOa0aVtoGDRoUl19+eUr5ueeeG3/84x9LrJ+pU6eW+6p0W7ONGzfGv/71r3jooYfi448/LlZbZZ0wl/+m2QULFqRdWSxTK1asSClbsGBBxsna1apVS1nFMRPpbnwt7Cbxjz76KKWsOAlFmerfv3/cdNNNsXr16s1lAwcOjIEDBxZYZ8OGDfHQQw8llXXs2DGnJMGSMmzYsBJJmu3evXva5K7ScN5558VVV121+fXq1avjpJNOiv333z/OPffc6N27d077XmmaNGlSUkJnRGS9etyW0iXXjR07Nu2Nj1smmmzSuXPnnPpt3759VKtWLWm/z1WuMaTz3HPPxX333RfvvfdebNy4Med2ch23d9lll6zr1K5du1TayTVZ+Kcu/0qWmapbt26JJGvnX8kyU+l+R/lXRCY3K1euTFktrFOnTjk/DKagcTsbLVq0iKZNm+bUf0H7Srq40iVi5fpAgYIsWLAgq+1L6pixLc/18+8vO+64Y9bJGpvsu+++UaFChaRjZrb7Y9OmTaN58+Y59V8WyvIcoTzneQXZHuYm2/J7ePvtt+Pvf/97vP7667Fu3bqs+9+kqESoghRnXrOlot53/jlHcY5TucyFtsXzwtKWfyyvXLly7L333jm11apVq2jcuHHMnz+/wPZ/anKds1eoUCH23nvvGD58+OayiRMnxg8//BA1atQoqfDYhixZsiRmzJiRVFac+W6nTp1KJFm7VatWWT/sJaLga7nbU7J2/rll48aNcz7e5mprmhtFFP4d558jVKpUKefjUa5jLwAAAECuJGsDAAAAbONeeOGF6NevX0qC2cknnxz/+te/Ii8vr5wi+2mZOHFinHnmmfHpp5+WSHtlnTCX/ya/lStXJq0yVRIWLlyY8Q1dDRo0yKmPdDcFFnaD+9y5c1PK9txzz5z6zkajRo3itNNOi8cff3xz2b///e/4y1/+kvYGtoiIl19+OWbOnJlUNmDAgFKNc3s0YMCAeOqpp2L06NFJ5SNHjoyRI0fGJZdcErvsskscfPDB0aVLlzj44INjr732KtexNF1SWocOHXJur2PHjhn1EfHj73ZLVapUyWm1pogfb65s2bJlTJ48Oaf6W2rSpEmx25g1a1acffbZ8c477xS7rYjcx+369etnXSfdWFcS7axfvz7rNii5Y1YuCVmVKlVKWYksU23atIkqVarE2rVrN5fNmzcvp7ZItnDhwpRVT4szbrdv3z4lOTbbhOXddtutWP3nV9C+kn9OGRGlMqfMRkkcM7bluX4ikUj5zIqzP9aqVStatmwZ33333eaybPfHkvhOSlP+c4RKlSoV6zMrTHnO8wqyPcxNtqb3kOnxfdmyZXHhhRfGM888k3WfBckl2a2k5jVFfXf5jyMlfZwqSlmcF7788stx/fXXZxVXly5d4uGHH86qTknJP1a0bt06qlWrlnN7HTt2THooW7Zj0famuPv4lsnaiUQiFixYEDvttFNJhMY2Jt1cuDgPV915552LEc3/U1bXcrdF+Y95ZXHtOb+taW4UUfh3nP/z2mmnnXI+HrVr1y4qVqwYGzZsyKk+AAAAQLYkawMAAABsw1555ZU4/fTTU26CPeGEE+Kpp57KefU+svPFF19Ez549k1YMKq6yvClt1apVsWrVqjLpJ1O5rMSSi0WLFqWU5XLTWS4uvfTSpGTtFStWxKBBgwpMwL7//vuTXteoUSPOOeecUo1xe1S1atV49dVX4+c//3m89dZbabeZMmVKTJkyJR577LGI+PGG02OPPTZ+/vOfx9FHHx0VKlQow4gjFi9enFKW6Sr16aTbx9P9FtL1nW7Fo2wUt/4mderUKVb9mTNnRvfu3WPKlCklEk9E7slEJTXeldW4Sary/Oxr165drIdJ1KlTJylxpqxX+91elfS4XaFChahTp07S91PQuF2Q4oy/6eoWtK9km0idi2znrcU9Zmzrc/1ly5alPNirOPtjxI9ziS2TtbPdH4v7nZS2/O+nbt26pfbgnvKc5xVke5ibbGvvYdmyZXHUUUfFyJEjS7TdXMaasnrP+Y8jJX2cKkpZnBcuWrQo6weWFHd8Lo7841FJHCu2tGbNmp/0atClMReTrP3TlG7uUNZjaDquSaS3fPnylONxWV173tK2NDcqyTlCXl5e1K5d27UOAAAAoMyU7R1lAAAAAJSY119/PU4++eSUm32OOeaYePbZZ90gVUbWrVsXp556atrkjYMPPjhuvPHGeOWVV2LcuHExb968WL58eaxfvz4SiUTS37nnnlsO0f8o3U1+PxXLli1LKatZs2aZ9N21a9fYb7/9ksoGDhyYdtspU6bEm2++mVR2xhlnlNgNlT81jRo1ijfeeCOefvrp2HfffYvcftGiRfHvf/87jjvuuOjYsWM8//zzZRDl/7N8+fKUsuLsp+nqpusj4scb6rdUpUqVnPuN+DEpoiRUqlS8Z9H269cvbaL2PvvsE9dee228+OKLMXbs2JgzZ04sW7Ys1q5dmzJu33DDDcWKAUpCcY9Z+esXNBaQnZIet9PVz/a7KqvjxtY4ryzOMWN7mOtvjftjcY/jpS3/OUK2KxNnozzneWw9rrnmmrSJ2u3atYurr746nnnmmRg9enTMmjUrli5dGmvWrEkZZx599NFyiDx3+ffLkt7vM7GtnReWtpL8Tgqq/1Mej4ztlJT812kiinetpqSu05BeumvPpTm33B6UxfEIAAAAoLRs3f8XFAAAAIC03nrrrTjxxBNTbs468sgj44UXXih2Mh2Ze/DBB2PixIlJZW3bto3//ve/0aVLl4zbKYuVrQtSvXr1lLJu3bqV+KpeW6N0q/qtXLmyzG6au+yyy5JWxx4/fnyMGDEiDjzwwKTtHnjggUgkEkllBa3ATWby8vLi1FNPjVNPPTUmTpwYr732Wrz33nsxYsSIQlcFnTRpUpx88skxYMCAuO+++0ptlcUt1a5dO6Vs5cqVObeXrm66PiJSV68p7g3h6W5SLWuvvvpqyup5TZo0iSeffDJ69eqVcTvlOW7DJsUZC9LVL2gsIDslPW6nq5/td1VWx41088pVq1ZFtWrVcu6/PG0Pc/2tcX/c2uU/R1ixYkWp9VWe8zy2Dp9//nk88sgjSWW1atWK+++/P84444yMzze2tblp/lUuS3q/z9S2dF5Y2kryOymo/k95PDK2U1LSPbixONdqtobrNNuzdNeeS3NuuT3IP76VxvEIAAAAoLRYWRsAAABgGzNs2LA44YQTYvXq1UnlPXv2jMGDB2+ziRDbqv/85z9Jr2vXrh1vvfVWVskbET+u0FRe6tWrl7K6XXnGU5YaNmyYUlaWK0Keeuqp0bhx46Sy/Ktrr1mzJmWVtK5du2a08heZ6dChQ/zyl7+Ml19+ORYsWBBff/11/Otf/4qzzz47GjVqlLbO/fffH7feemuZxFe/fv2Usi1vos9WuroNGjTIqO/ly5fH2rVrc+67sISHspJ/3K5YsWIMGTIkq0TtiJ/OOMnWbfny5SkP88hG/hvz69WrV8yIMrNu3boy6ae8lPS4vXHjxpTvqqBxuyBLly7Nuf90dQvaV9IdN7fl8XJ7mOvXqVMnKlRIvi2gOPtjuvrZ7o9bu/znCEuXLi3WWFuY8pznsXV4+umnU/avxx9/PM4888ysEoC3tbE2/3GkpI9TuSjp88J+/fqlrIBe1N+7775bIu8lF/nHo5I+VlStWjVq1KhRrDYzsbXOM8tqLlaSttbP8qcu3dyhONdatobrNNuz2rVrR+XKlZPKyvLa87aoJOcIiUSi2A+eBAAAAMiGZG0AAACAbch7770XvXv3Tlkx6bDDDoshQ4akXcmO0rNixYr46KOPksrOOeecaN26ddZtffvttyUUVfby8vJSEoZnzpwZ69evL6eIyk6zZs1SysaPH19m/VetWjUuvPDCpLLnnnsu6UbJZ599NuXGyUsuuaRM4vupateuXZx//vnxxBNPxJw5c2LIkCHRtWvXlO1uvfXWWLBgQanHk//3GREpq3xm48svv0wpKyj5oGXLlkmvE4lETJgwIad+Fy5cGLNmzcqpbkl68803k14fffTRsd9++2XdTnmO27DJ+vXrc94Xp06dmvLwhSZNmhS4ff4bzCNyT+DY3hMCGjVqlJJgV5xxe9KkSbFx48aUPrLx9ddfF6v//AraV5o2bZpS9t133+Xcd3nanub6+feX4uyPK1eujOnTpyeVZbs/bu3ynyOsX78+7fypJJTnPI+tQ/656e677x59+/bNup1tbW6a/ziS7liTqa+++qq44aS1tZ0Xlrb849HUqVNjzZo1ObeXfzwqaizKP9fc3uaZJTkXS3ds39L2/ln+1DVp0iSqVq2aVPb555/n3F5ZXgf9qco/tyzO9/VTkH+OMH369JQHF2dq8uTJsWHDhpIICwAAACAjkrUBAAAAthHDhw+P4447Ln744Yek8kMOOSReffXVMlmdhmSzZs1KSZw55JBDsm5n7ty55X5jdbdu3ZJe//DDD/HJJ5+UUzRl54ADDkgp+/DDD8s0hgEDBkTFihU3v169enXSStr5V9quX79+nH766WUW309dxYoVo3fv3jFixIg45phjkv7thx9+iKFDh5Z6DLvuumvUqlUrqWzMmDE5t/fxxx+nlBW0Unu6JOaRI0fm1G+u9UrSmjVrYt68eUlluYzbGzZsiNGjR5dUWFAsuR6v09UraCyI+HF13vzyr/aciXXr1qUkem5vatSoEbvttltS2WeffZbzTeLZjNsFmTFjRsr4l6ls9pX8c8qIiPfffz+nfsvb9jTX79y5c9LrGTNmxNy5c3Nq65NPPkn5XLLdH7d2ZXmOUJ7zPLYO33//fdLrXMaZiEh5uMTWLv9+OXPmzGKNS6VtazgvLG35jxXr16+Pzz77LKe2pk+fnjLvKGosyj/XzGWeGRExZcqUnOqVtlz3040bN6Z8Dx06dCj0OvD2/ln+1FWuXDn22WefpLLRo0enzM8ytTVcq9ne5Z9bzp8/v1gPcNje5T9erF+/PsaNG5dTWz+F/78BAAAAbF0kawMAAABsA0aMGBHHHntsrFy5Mqn8oIMOitdeey1q1qxZTpH9tKVbOalBgwZZt/PMM8/kHMOWSb4RkXMS0JFHHplS9sILL+TU1rbk4IMPjkqVKiWV/ec//ynTFTdatmwZJ5xwQlLZAw88EIlEIsaPHx8jRoxI+rdzzz03qlevXmbx8aNKlSrFbbfdllJe2ApE+fetiNx+oxUrVkxJmv7qq69yXuH62WefTSk78MAD027brVu3lNVhn3rqqZz6HTRoUE71SlK6lcFyGbdfe+21WLFiRUmEBMX20ksv5VQv3XF+//33L3D7WrVqpcw7cklAHT16dKxatSrreiU1ppaV/OPqihUrck7kymbcLkwu+8rGjRtj8ODBSWXVqlVLSRDZZHuaU25Pc/10+8tzzz2XU1sltT9uzbp3755S9uSTT5ZKX+U5z2PrkH+syWWc+fzzz4u1Int5SDfnePHFF3NqqyyPM7mcF24ryvtYUa9evaTXucwz165dm3Piaf65ZknPM4cNGxZLly7Nut5bb72Vkmxd2Jw9IvWznDZtWiQSiaz7fu+997KuE1H6nyWpyb9z5syJYcOGZd3O119/XayHxJSnkponl4WynFtuD7bVOQIAAABAhGRtAAAAgK3eqFGj4phjjklJCjvggAPif//7X8oqXJSddEny6ZI6CrNu3bq45557co6hdu3aSa9zTR487rjjUm5yu//++2PJkiW5hrZNqF27dhx++OFJZdOmTStWUk0uLrvssqTXU6ZMibfeeivuv//+lG0HDBhQVmGRT/v27VPKCrvZOv/vMyL33+hRRx2VUpZu/yjK8OHD44svvkgq22uvvaJp06Zpt69fv3706tUrqeyDDz7IeuW+b775Zqu4QbIkxu2IiLvuuqskwoES8dJLL8X8+fOzqjN//vyUBNwGDRqkJAxuKS8vL3bdddekslxWmH/wwQezrhNRsmNqWSipcXvq1KkpSd6NGjVKWf0yEw8//HDWdf73v//FjBkzksoOP/zwqFy5ctrtO3bsGO3atUsqGz16dLzzzjtZ913etqe5frr98cEHH8x6BcalS5emPLSlcuXK0aNHj5zi2lp16NAhdtttt6SyXOY/mSqveR5bh/xjzU9lbnrkkUemJHQ+/PDDWSeUfvbZZ2WeaJjteeG24vDDD0+5LvTkk0+mPDiyKOvXr4+HHnoopTz/eWV++cfdr7/+OuvPddCgQVnHu0lJHXMLsnr16vj3v/+ddb10n2X+1d3zy/9ZrlixIr788sus+h02bFjOK2uX9mdJxGmnnZZSduedd2bdzh133FES4ZSLbWk/6927d8ox74EHHsh51fvtXbdu3VIeXvPkk0/G6tWrs2pnzpw5MWTIkJIMDQAAAKBIkrUBAAAAtmKffPJJHHXUUSk37uy3334xdOjQtEkrlJ0ddtghpeyNN97Iqo2bbropJk+enHMM9evXT3qdy8pDERGtWrWKs88+O6ls2bJlcd555+W0+s625Le//W1K2RVXXBGzZ88usxh69uwZHTt2TCq74447Um7k7dmzZ8pNt5SddPtE48aNC9w+/+8zIvff6Pnnnx/VqlVLKrv//vuzWsFt/fr1cfnll6eUpyvb0iWXXJJSNmDAgPjhhx8y7vfiiy+ONWvWZBZoKapbt27UqFEjqSzbcfvhhx+Od999twSjguJZtWpV/O53v8uqzu9+97uU3/B5550XVatWLbTevvvum/R6zJgx8fXXX2fc7yeffBL/+c9/Mg90C7Vr1065wT3XMbUs9OnTJ2Wu+Morr8T//ve/rNq5/PLLY/369UllF198cYHJ0oX5+OOPs1rBbd26dfGrX/0qpbyoB8dcd911KWX9+/ePRYsWZdz31mB7muvvt99+0aVLl6Sy8ePHZ50QfN1116V8j6eeemo0adIkp7i2ZunOEfr165dzEmBhynOeR/nLP9a89dZbWT1I4a233orHH3+8pMMqdTvssEOccMIJSWWffPJJVu8lkUiUyz6e7XnhtqJ58+bRp0+fpLK5c+fGTTfdlFU7f//732PSpElJZQcddFB06tSp0Hr555nr16/P6kF6S5cujT/+8Y+ZB5pPSR1zC3PjjTfG4sWLM97+/fffT1ndvFmzZvGzn/2s0Hr5P8uISHnYSmHWrVuX9fnFlvJ/llOnTt3ury2Wtf333z/lNzV06NCsHgjwzjvvxL/+9a+SDq3MlMVvtqS0bNkyzjjjjKSy+fPnp73eRkTVqlWjX79+SWWzZs2K22+/Pat2fvWrX20V1yIBAACAnxbJ2gAAAABbqXHjxkWvXr1SVpHp0qVLvPHGG1GnTp1yioxNmjRpkrLC5KBBg2LcuHEZ1X/00UfjtttuK1YMe+65Z9Lr9957L+cEguuvvz4lSeull16Kiy66KOcbm6ZNmxaXX355ygpvW5MePXrEIYccklS2YMGC6NWrV8pKkpmYNm1aTnFceumlSa/ffPPNWL58eVKZVbWLZ8SIEXH33XenfK6Zuvvuu1PK9t577wK3b9myZdStWzep7LXXXsup70aNGsU555yTVLZ+/fo46aSTMnqwQCKRiP79+6eMT02aNImzzjqr0Lq9e/dOWcF1/Pjxcfzxxxe50tnq1avjrLPOirfffrvIGMvKwQcfnPT63Xffzfh7GTp0aFxxxRWlERYUyyOPPJLxqskPPfRQPPLII0lllStXzuhG8XSr+KVL5k1n+vTpceqpp8a6desy2j6/ChUqpDzY5PXXX896ZeCyUrly5bQJZOecc07GKxtef/318eqrryaVVatWLX7xi1/kHNdll10WY8eOLXK7RCIRF1xwQXz11VdJ5bvssksce+yxhdY966yzUlYdnTp1ahx77LExa9as7IOOHx8i9Je//CWnFSlztb3N9a+55pqUsl/96lfx/vvvZ1T/kUceifvuuy+pLC8vL66++uqc4tnanXXWWdGmTZuksq+//jqOO+64WLJkSdbtFXaOUJ7zPMpf/nPRb7/9NuMHKYwdOzZ+/vOfb7NJkOnm1VdccUV8/PHHGdX/1a9+FR988EHW/Zb1eeG2JN2Y/te//jX++9//ZlR/6NChaR/a8stf/rLIur169YoKFZJvY7v55pszWl1703nn1KlTM4oznfzH3C+++CK+//77nNtLZ8GCBXHKKadkdI1t2rRpceaZZ6aUX3LJJUU+tOfAAw9MuRbxj3/8I7777rsi+924cWNcdtllMXr06CK3LUj+z3Lp0qUxYsSInNsjvf/7v/9LKbvgggvihRdeKLLu+++/HyeeeOI2e/yIKNl5clm49tprU367Tz31VFxzzTVZfw8bNmwo8fFpa5NurLvlllvilVdeyaj+P/7xjxg0aFBphAYAAABQKMnaAAAAAFuhL7/8Mo488siUVcs6d+4cb775ZsoNd5SfU089Nen1unXr4uijjy501dUlS5bElVdeGRdccMHmBKNck+8PPPDApNdLly6N0047LSZOnJh1WzvvvHM88MADKeUPP/xw7L///vHKK69kdPPY8uXL46mnnooTTzwxdtlll7j33ntj9erVWcdTlp588slo0KBBUtkXX3wRXbp0iQcffDBlRcv81q5dG6+88kocf/zx0bNnz5xiOOeccwrdD5o1axYnnnhiTm3zo3nz5sVVV10VO+64YwwYMCDeeOONjJIGV6xYEb/97W/j73//e1J53bp1o3fv3gXWy8vLiwMOOCCp7K233oprr7025s2bl3X8t912W7Ro0SKpbMqUKXHQQQfFW2+9VWC9mTNnxs9+9rO0q9Q9+OCDKSs55lexYsV49NFHU26SfOedd6J9+/Zx3333pbyfxYsXx+OPPx577LFHPP300xERUa9evZTkvfKQf9yOiDjttNNSVizb0qpVq+Lmm2+On/3sZ7Fq1aqIyH3chpJUtWrVyMvLi4gfV1u+7rrrCkz+WLNmTVx33XVpH/xx3XXXRdu2bYvsr2/fvikrmA0ZMiQuvPDClJW6t/TCCy/E/vvvv3m1s6LGnYLkn/dMmjQp+vfvn1HiSXn45S9/Gfvss09S2YIFC6J79+6bx8Z0lixZEv3790+7OuSf//znaN68edaxbPrMly1bFkcccUShSc+zZ8+OPn36pKzCnZeXFw8++GBKIlV+FStWjGeffTZq166dVD5q1Kjo1KlT3HfffRnNDdevXx9vvfVWXHTRRbHTTjvFb3/725gzZ06R9UrS9jTX//nPf56SaL9q1ao49thj49577y3wwQerV6+Oa6+9Ni688MKUc4Grrroq7eqd24PKlSvH008/nfIwq/feey+6dOkSzz77bJHnRitXroynn346Dj300DjvvPMK3ba85nmUv3Rz0yuvvDLuu+++AvexDRs2xD//+c/o0aNHLFiwICK2zbnpYYcdFueee25S2fLly6NXr16FrrC9cOHCOOuss+Kuu+6KiIjq1atn1W9ZnxduSw488MCUB/hs3Lgxzj777Ljxxhtj7dq1aett2LAh/vrXv0afPn1StunTp0/Kit3ptGzZMo466qikshkzZsRRRx1VaFLi2LFjo3v37psT+Epqnrlx48Y45ZRTYsyYMTm1l9+muN5+++04/PDD4+uvvy5w29dffz0OPfTQlAcItm/fPn7zm98U2Vf16tVTVvFdsWJFHHHEEYU+NGjKlClx/PHHx4MPPpgUc7byf5YREeeff34MGzZsq33Q0raoT58+KceQtWvXxkknnRSnnXZaDB8+POXz/vjjj+Piiy+OHj16bH5gRf7rVtuKkpwnl4X27dvHX//615Tyv/3tb3H44YdnNNbMnj077r777th111236VXRM7HLLrvE73//+6Sy9evXx8knnxx33nlnbNiwIW29H374IX75y1/GVVddFRE/nsPmn88DAAAAlKZK5R0AAAAAwLZkzJgxKQkXubr55pvjhBNOSPtvV155ZcyfPz+lfMmSJdG9e/dS67coxx57bFSpUqVY/Uf8uDp4pqs/lpSXX365RL67X//610kr21x99dVx7733Jq2uNmfOnOjRo0cceuihcdRRR0Xr1q0jLy8v5syZEx999FH873//ixUrVmze/vDDD48WLVrEE088kXU855xzTvzhD39ISiZ+9dVX49VXX4369etH06ZNU25Iat68eYGryJ577rkxceLE+POf/5xU/tlnn8Xxxx8fO+20U/To0SP23nvvaNiwYdSoUSOWLl0aS5Ysia+//jo++eST+Pzzzwu8gXdr1apVqxg0aFCccMIJSTdpz507Ny6++OL4wx/+EEceeWTsu+++0bhx46hWrVosWbIkvv/++xg7dmx88MEHm1d7atWqVU4x1KpVK84555y499570/57//79i1w9icwsW7YsHnjggXjggQeidu3a0blz5+jUqVPsvPPOUa9evahZs2asXr06ZsyYEWPHjo3XX3897Wped955Z5GJAeeff34MHTo0qez222+P22+/PXbYYYdo0KBBVKqUfKn+hBNOiJtvvjmlrQYNGsSTTz4ZvXr1SvrNT506NY488sjo3LlzHH/88dG6deuoVq1azJ49O95///0YOnRo2qS4Sy+9NH72s58VGv8me+21V9x7770xYMCApKSROXPmxKWXXhqXXXZZNGnSJBo2bBiLFy+OefPmpdw4ef/998fAgQOTVmmtWLFiRv2XpHPOOSduu+22+OabbzaXrVixIk455ZTNn+Euu+wSlStXjnnz5sUnn3wSr7zySixcuHDz9rvvvnv07t07ZayEstasWbM47rjj4r777ouNGzfGrbfeGg899FCcdNJJsddee0XDhg1j4cKFMX78+HjhhRfSPihi3333TbkJuiDVqlWLG264YfONz5s8/PDD8eqrr8bJJ58c++yzT9SuXTsWL14cX331Vbz22msxadKkzduefvrpMXv27Hjvvfeyfr/nn39+ymqjjz76aDz66KPRuHHjaNy4ccqxsjzmnZtUqVIlnnrqqdhvv/2S5n7z58+P008/PW688cbND7epXbt2zJ07N0aNGhUvv/xy2tU+jzvuuLSrdWeib9++MWHChBg3blwsXrw4zj777LjllluiT58+0bZt26hVq1bMmTMnPvjgg3j11Vc3P5hiS5dffnn06NEjo/722GOPGDRoUPTt2zfpmDVv3ry49NJL47rrrovDDjssunXrFk2aNIm6devGypUrY8mSJTF9+vT45JNP4tNPP41ly5bl9H5LyvY213/00Udjn332SVqteeXKlXH55ZfHHXfcEX379o0OHTpEvXr1YsGCBfHZZ5/Fiy++uDkZdEudO3cu9srhW7suXbrEvffeGxdddFHS/Oebb76JU089NXbcccc46qijYs8994xGjRpFpUqVYsmSJTF16tQYO3ZsfPjhh5sfZHHYYYcV2ld5zvMoX4cffngceuihSavcr1+/Pi699NK4++67o0+fPtGxY8eoXr16zJ8/P7744osYPHhwzJo1a/P2TZs2jV/+8pcZJXFubf72t7/FsGHDYvr06ZvLlixZEv369Ytbbrkl+vbtG+3atYtatWrF3Llz46OPPopXXnklaZz94x//GL/61a+y7rsszwu3JX/9619j+PDh8cUXX2wuW79+fdx0000xcODA6NOnT+y1117RqFGjWLx4cXz55ZfxwgsvpCQWR/yYgJ3NPOzmm2+ON954I+lcctSoUbHbbrtF375946CDDopGjRrFihUr4rvvvou33347Pvzww81jdLt27eL444/fnMifjZ/97GfRoEGDpAdnjho1Krp27Rq1a9eO5s2bp01e/uyzzzJq/4Ybbog//OEPsWHDhvjwww9j9913jyOOOGLzPGHt2rUxbdq0GDJkSHzyyScp9atWrRqPPvpoxgnUv/vd7+Lf//530pxyypQpsffee8fxxx8f3bt3j2bNmsXq1atj5syZMWzYsBg2bNjmY1CjRo3iyiuvTLt6c1G6desWHTt2TEoM//rrr6Nnz55RvXr12HHHHaNGjRop9V577bWcHkr0UzZw4MCYOHFifP7550nlzzzzTDzzzDNRo0aNaNasWVSsWDFmz56dNHZG/Difu/766+OYY45JKi+PazXZKul5clm4/PLLY/To0SkPzho2bFh07do19tprrzjyyCOjTZs20ahRo1i3bl0sXrw4Jk6cGGPGjIkxY8b8pB54cN1118Urr7ySNCauWbMmfv3rX8fdd98dJ510UnTo0CHq168f8+fPj08//TRefPHFpHH80ksvjSFDhmy1D3gDAAAAtj+StQEAAACysHLlyhg3blyJtJV/1ewtFbSiz6bVCEur36KU1MoU9erVK5F2srF48eJYvHhxsdvJn0TfoEGDzUm++RMT33///aQbrtPZY4894tlnn42rr746p3h22GGH+MMf/hA33nhjyr8V9J63TDZJ5/bbb4+WLVvGNddck5J0PX369EJXuNqWHX300fHGG2/ESSedlPI7mT9/fjz11FPx1FNPlWoMl156afzzn/9MWUGtYsWKcdFFF5Vq3z9Vy5cvj/feey/rpMGrr746+vfvX+R2J510Uhx++OHx9ttvp/zb7Nmzk5KlNinswRI9evSIwYMHx6mnnhorV65M+rexY8fG2LFjiw4+frxBNP+KcEW56KKLIi8vLwYMGJByc2gikYi5c+fG3LlzU+rl5eXF3//+9zjttNPinnvuSfq38lgBsHLlyvHss8/GwQcfnLIScCafYYsWLeKVV16Jxx57rBSjhMzdddddMX78+Pjggw8i4sdjVv6E5oLstdde8frrr2f1MJDLL788hgwZkjKuzZ49O+U3nt+hhx4ajzzySEoyQKa6du0a/fr1S/v7mz9/ftqHHZXHvHNLHTp0iGHDhsVxxx2Xkiz/1Vdfxe23355RO3379o1BgwZtXkk9W5UrV44XX3wxDjjggM1j9VdffZVxsu1ZZ50Vf/vb37Lq8/jjj4+33347TjvttJQVsZcsWRKDBw+OwYMHZ9VmWdve5vpNmjSJ4cOHx9FHHx1TpkxJ+rfp06dnPDc4+OCD4+WXX/5JrFLXv3//qF27dpx33nkpDzGYMWNGia5qWJ7zPMrXk08+Gfvtt1/KXPrrr78u8uFAderUiVdffTUlUW9bUb9+/XjnnXeie/fuKcm+kydPLvL9n3766XHNNdfklKy9pdI+L9yWVK9ePd55553o3bt3jB49Ounf5s2bFw888EBG7XTo0CGGDh0aDRo0yLjvLl26xPXXXx833HBDUvmqVati0KBBMWjQoALr7rDDDvG///0vnnzyyYz721K1atXirrvuin79+qX82/Lly5MePpSL/fffP+6+++647LLLIuLHBPihQ4emPNwtnSpVqsRzzz0X+++/f8b97bTTTnHPPfekvJ/169fHiy++GC+++GKBdWvVqhWvvPJKsa4D33PPPdGrV6+U+dOqVati8uTJaetsaw9+3Bo0aNAg3nnnnTjyyCPTPjjghx9+KPD/J+yxxx7xyiuvxIQJE1L+rTyu1WSrNK6Jl4XHH388mjZtmnaV7fHjx8f48ePLIaqtU+XKlWPo0KHRs2fPlHnOjBkz4u677y60/iGHHBJ33nlnDBkypDTDBAAAAEhSobwDAAAAAIBt3bHHHhvPPvts1jey9e7dO4YPHx7169cvVv//93//F7fcckuJrHq+yaWXXhrDhw+Pgw8+uFjtVK9ePU4//fTYaaedSiiy0tW9e/cYPXp0HHfccTm30bRp05zrtm/fPg4//PCU8uOOOy5atmyZc7v8qG7duhmvQlWQxo0bx7/+9a+MV+qqUKFCPPfcc3HGGWcUq98tHXvssfH+++9Hly5dsq7bsGHDGDhwYPzjH/+IChWy/18EF154YYwaNSr23XffjLZv06ZNDB06NK644oqIiJSbZevWrZt1DCWhU6dO8frrr8cOO+yQVb39998/Ro4cGa1bty6dwCAHVatWjaFDh2a9guoJJ5wQb7/9djRs2DCrehUqVIghQ4ZE7969s6p31llnxeuvv17slSfvv//+uPLKK3Maw8pLly5d4qOPPoojjjgi67o1a9aMm266KZ599tliH8N23nnnGD58eHTo0CHjOpUqVYrf/va38dhjj+X0mR966KExduzYOOuss4q1Ql9eXl706NEjDjnkkJzbyNX2Ntdv27ZtjBgxIk499dSsk/8rV64cl19+ebz55pvFfl/bktNOOy0++OCDYp0bZXqOUJ7zPMrPTjvtFO+8807stttuWdXbbbfdYsSIERnPzbdWbdu2jffeey8OOuigrOr94he/iH//+99Zj2XlcV64rWncuHEMGzYsBgwYEJUqZbcOSF5eXpxxxhnx4Ycf5nQt6Prrr4+bbropq++1c+fO8dFHH0Xbtm2z7m9L5557bjz88MNRu3btYrVTkEsvvTQeeuihrPa/li1bxquvvpr13Dvix/fzyCOPZPUdtmnTJj744IPo1q1b1v1tqWfPnvHiiy8W6xoZmWnUqFGMHDkybrjhhowepFOxYsW4+OKL48MPP4wddtghbVJzeV2ryVZpXBMvbRUqVIg777wz/vvf/+Z8bSkvLy8aN25csoFtpRo1ahTvvPNOnHDCCVnV69u3bwwdOvQn8XApAAAAYOvi/9ABAAAAQAno06dPjB8/Pi6++OJCk5AqVKgQ3bt3j8GDB8eQIUNKZLXHChUqxO9///uYOXNm3HvvvXHaaafFHnvsEY0aNSrWDcj77bdfDB8+PIYPHx5nnnlmNG/ePKN6zZs3j7PPPjueeOKJmD17dvznP/+JJk2a5BxHWWvbtm288sorMXLkyDjzzDMzuvmtSZMmceaZZ8Yrr7wSH330UbH6T5eYcckllxSrTX7Uo0ePWLhwYbz00kvxi1/8IvbZZ5+ME8f23XffuPPOO2Py5Mlx/vnnZ9VvvXr1YtCgQfHVV1/FjTfeGL179462bdtG/fr1s1rNdkudO3eO0aNHx9NPPx1HHHFEkTcfduzYMa6//vr45ptvYsCAATn1uUmXLl1i9OjR8c4772z+HJs2bRqVKlWK2rVrR8eOHePss8+O5557Lr7++uvo1avX5rr5V1bNZpW1knbwwQfHuHHj4je/+U2RY3GXLl3i8ccfjw8//DB23HHHsgkQslCzZs146aWX4tlnn42uXbsWuF1eXl4cfPDB8fzzz8fgwYOjUaNGOfVXvXr1GDJkSDz99NOx1157Fdnfa6+9Fk8++WSxE6MifkxO//vf/x7Tpk2Lv/zlL9G3b9/YbbfdomHDhlv1Tfpt2rSJN998M9544404/vjjo2bNmkVuf/XVV8eUKVPi+uuvL7HEy3bt2sWnn34af/nLXwpNoKpWrVr07ds3xowZE7fffnuxEq132GGHePLJJ2Py5Mlx1VVXZZwsXrt27ejdu3f8/e9/j6lTp8Y777xT7MShXG1vc/3GjRvH008/HaNHj47TTjutyMTrHXbYIS688MKYOHFi/OMf/yiR3/K2pnPnzjF8+PAYOnRo9OnTJ6MkppYtW8aFF14Y7733Xjz99NNZ9VVe8zzKT8eOHWPMmDFxyy23RLNmzQrdtkOHDvGPf/wjxo8fH7vvvnsZRVi62rRpE8OHD4+HHnooOnXqVOB2FSpUiMMPPzzeeeed+Oc//5nT8am8zgu3NTVq1IiBAwfGF198Eeeff36R+2WDBg3i5z//eXzyyScxaNCgYj3U4/rrr4/Ro0fHUUcdVWii8S677BL33HNPjBo1Klq1apVzf1u64IILYubMmfHoo4/G2WefHZ06dYomTZoU+4FDm/Tv3z/Gjx8fZ599dqFttmzZMn7/+9/Hl19+mdMDfzY577zzYsKECXHKKacUejxp3rx5/OlPf4rPP/889t5775z729Lxxx8f06ZNi2eeeSYuuOCC2G+//aJZs2ZRs2bNrB+yQOGqVq0aN954Y0ybNi3uvffe6NWrV+yyyy5Rs2bNqFKlSjRr1iy6d+8eN910U0yePDnuv//+zQ8iyn+dJqJ8r9Vko7SuiZeF0047Lb7++ut44IEH4rDDDsvoXHavvfaKa6+9NiZNmhSXXnppGUS5dWjUqFEMHjw4nn/++Tj44IMLHT+6desWzz//fDz//PNRo0aNMowSAAAA4Ed5iUQiUd5BAAAAAMD2ZM2aNTFq1KiYNGlSLFy4MDZu3Bj16tWLtm3bRteuXbeZG97S+frrr2PixImxcOHCWLhwYaxbty5q164dderUiZ133jnat2+/TSVmZyKRSMS4cePim2++ifnz58eiRYs2J6W2bNkyOnToEG3atCmRG003bNgQO++8c3z//feby9q0aRNTpkxxI2spWblyZUyePDm+/fbbmDNnTixfvjzWrVsXtWrVirp168Yuu+wSe+2111a/qtDKlStj5MiRMXv27Jg3b16sXbs2GjVqFE2aNIlOnTptFSuzT548OXbdddeksn/9619bRZLDhg0bYsyYMTFhwoRYsGBBrF+/PmrXrh0777xzdOnSpcjEBCgr/fr1i8cff3zz61atWsW0adNStpsxY0Z8/PHHMW3atFi5cmU0aNAgdthhh9hvv/2iRYsWJR7X999/Hx999FHMmzcvlixZEjVq1Iidd9459t9//6xXsP+pWLt2bYwaNSq+//77mD9/fqxcuTIaNmwYjRs3jj322CNlvMxW69at47vvvtv8+txzz43HHnssZbsvvvgixo0bF7NmzYp169ZFkyZNYscdd4yDDjqo1FaVjIiYO3dujB07NhYsWBALFy6MFStWRM2aNaNOnTrRokWLaN++fbRq1WqrnP9sj3P9TcfBadOmxfz582PZsmVRr169aNKkSey6666FPpThp2rDhg3xySefxLRp02LBggWxePHiqFq1atSuXTtat24dHTp0yGlF2XS2hXkeJSuRSMT48ePjs88+iwULFsSqVauidu3a0apVq9hnn31yXolzWzJlypT47LPPYtasWbF8+fKoXbt2tGnTJvbff/+cHzZTmO3lvLA0bbo2MmXKlM1zvjp16kTjxo03nzeV1MNltrR06dIYPnx4zJw5MxYuXBiVKlWKFi1aROfOnTN+AExZe/fdd6NHjx5JZcOGDYvu3bsnla1atSpGjRoVX331VSxatCiqVq0aO+ywQ7Rr1y66dOlS4vOgH374IT788MP47rvvYsGCBZGXlxdNmzaNvffeO/bZZ5+tct5F6TvzzDPjqaee2vy6ZcuWMX369HKM6Kdp5cqVMWrUqJg9e3YsWLAgli9fHjVr1ox69erFLrvsEh07doyGDRuWd5hbhZkzZ8bo0aNj1qxZsXjx4qhZs2a0bt261K53AAAAAGRDsjYAAAAAwFZiyJAhccIJJySV3X777fHb3/62nCKCkvP3v/89rr766qSyzz//PPbYY49yigi2PZkma0OmydoAAJSsTJO1obytWbMmdtppp5g3b97mspNOOimee+65cowKAAAAALZdJf9IUwAAAAAAcnLPPfckva5WrdpWseowFNfatWvj7rvvTipr1KhRdOzYsZwiAgAAAPjpevzxx5MStSMiDj300HKKBgAAAAC2fZK1AQAAAAC2Ah9//HG8+eabSWVnnHFGNG7cuJwigpJz9dVXp6z+e8EFF0SFCv43BQAAAEBZmjJlSvzmN79JKqtevXqcddZZ5RQRAAAAAGz73AUFAAAAAFDO1q9fH5dddllSWV5eXlx11VXlExCkMWTIkHjhhRdiw4YNGddZu3ZtXHLJJXHfffcllVeqVCkGDBhQ0iECAAAA/GT84Q9/iOnTp2dV56OPPoru3bvH0qVLk8rPPPPMaNCgQUmGBwAAAAA/KZK1AQAAAADK0aRJk+KEE06I0aNHJ5Wffvrpseeee5ZTVJBqwoQJcdJJJ0Xr1q3jiiuuiKFDh8bcuXNTttu4cWOMHz8+/vznP0fbtm3j/vvvT9nmxhtvjNatW5dB1AAAAADbpzvvvDPatGkTvXr1in/+858xfvz4WLduXcp2ixYtiiFDhkSfPn3i4IMPjpkzZyb9+w477BC33XZbWYUNAAAAANulSuUdAAAAAADAT8k+++wTET8mtM6aNSsWLlyYsk2tWrXilltuKePIIDMzZsyIe+65J+65556IiKhXr140aNAgqlevHsuWLYsFCxbEqlWrCqx/5JFHxrXXXltW4QIAAABstzZs2BBvvvlmvPnmmxERUbly5WjSpEnUrVs31q9fH4sXL44FCxZEIpFIW79KlSrx5JNPRqNGjcoybAAAAADY7kjWBgAAAAAoQ+PGjStym3/84x+x8847l0E0UHxLliyJJUuWZLTt+eefHwMHDowKFSqUblAAAAAAP0Hr1q2LmTNnpqyenU7Tpk3jhRdeiAMPPLAMIgMAAACA7ZtkbQAAAACArUSVKlXijjvuiPPOO6+8Q4EUnTp1io4dO8aXX36Zdd399tsvrrvuujjhhBNKITJKy5gxY6J///6l2seUKVOiWbNmUatWrVLtp0uXLvHwww+Xah9sve6///64//77S72fAQMGxIABA0q9H/gpmTVrVhx77LGl3k/z5s3jtddeK/V+ADJRFvPwCHNkti6O+bnp06dPDBkyJFauXJlVvVq1asVFF10Uv/nNb6Jp06alFN3W5+WXX47rr7++1Ps54YQT4uabby71fgAAAADYukjWBgAAAAAoJ3l5eVGrVq1o27Zt9OzZMwYMGBDt2rUr77AgraOOOiomTJgQkydPjvfffz9GjhwZkydPju+++y4WL14cP/zwQ+Tl5UX9+vWjQYMG0bZt2zjkkEOiR48e0bVr1/IOnxysWLEixo0bV+r9fPPNN6XeR7169Uq9D7Zec+bMKZN9ec6cOaXeB/zUrF27tkx+v0uWLCn1PgAyVVbzcHNktiaO+bn5z3/+E6tWrYrhw4fHiBEjYty4cTF16tSYNWtWrFy5MlavXh21atWKBg0aRJMmTaJLly5x6KGHRq9evaJ+/frlHX6ZW7RoUZnsZ/vss0+p9wEAAADA1keyNgAAAABAGUokEuUdAhRLu3btol27dnHBBReUdyjwk/PYY4/FY489Vt5hsA2YNm1aeYcAAPCT1L17d9d+KFPVq1ePXr16Ra9evco7FAAAAAD4SatQ3gEAAAAAAAAAAAAAAAAAAABsi/ISHuUJAAAAAAAAAAAAAAAAAACQNStrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYAAAAAAAAAAAAAAAAAAEAOJGsDAAAAAAAAAAAAAAAAAADkQLI2AAAAAAAAAAAAAAAAAABADiRrAwAAAAAAAAAAAAAAAAAA5ECyNgAAAAAAAAAAAAAAAAAAQA4kawMAAAAAAAAAAAAAAAAAAORAsjYA8P+xd6fRVVdn/7jvhEFmEBE0ykxbBLXO4gBIq2JbFTqAaCmgqKht1WeBWudqdVmwOFVbi1UB9akVi0hFrTgAKooDgkJwQJkEZBDIDwIIQv4vfHr+nDAlOwlBva61sta599n7/t6H4QVZfLIBAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIEHVyh4AdherVq2KiRMnZuqmTZvGHnvsUYkTAQAAAAAAAAAAAAAAAACwI1988UUsWLAgU3fu3DkaNGiwy54vrA3/Z+LEidG9e/fKHgMAAAAAAAAAAAAAAAAAgERjxoyJbt267bLn5e6yJwEAAAAAAAAAAAAAAAAAAHyDCGsDAAAAAAAAAAAAAAAAAAAkqFrZA8DuomnTpln1mDFjok2bNpU0DQAAAGU2e3ZE9+473jNmTIR/+wEAAAAAAAAAAADA19bs2bOj+xb/b7h4XrSiCWvD/9ljjz2y6jZt2kT79u0raRoAAAB2iTZtIvzbDwAAAAAAAAAAAAC+MYrnRSta7i59GgAAAAAAAAAAAAAAAAAAwDeEsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkqFrZAwAAAAAA6YqKimLq1Kkxbdq0WLp0aURENGnSJL7//e/HYYcdFjk5OZU63/r162Py5Mnx/vvvx8qVK6N69eqx//77x9FHHx2tWrWq1NlKa/HixfHhhx/G/PnzY/ny5bF27dqoXr161K9fP1q0aBFHHHFENGzYsLLHBAAAAAAAAAAAAHYhYW0AAACAStKiRYuYN2/eVuv33ntvDBgwIKnn8OHD4+yzz95qvXnz5jF37tyknuyeNm7cGHfeeWfccccdsXDhwm3u2X///ePSSy+Niy++OKpVq7ZL51u2bFnccMMNMXz48CgsLNzmnsMPPzyuvfba6NatW4XMcOaZZ8ajjz6atVaavwvz5s2LRx55JF5++eV46623Yvny5Ts9c9RRR8X5558fffv2japVffsVAAAAAAAAAAAAvulyK3sAAAAAALKNHDky+eyIESPKcRJ2VwsWLIijjz46Lrvssu0GtSMiPv300xg0aFAcc8wxO9xX3iZMmBDt2rWLe+65Z7tB7YiIt99+O7p37x59+/aNDRs2lOsM//73v7cKapfW+PHj4+qrr45nn322REHtiIg33ngjzj333DjyyCNjxowZZXo+AAAAAAAAAAAAsPsT1gYAAADYzUyePDk+/vjjUp+bN29eTJw4sQImYneydOnS6NKlS7zzzjtZ6zVr1oz27dvHAQccEDVq1Mh67+23344uXbqUOHBcFq+88kr8+Mc/3upZDRo0iEMPPTRatGgRVapUyXpv5MiRceaZZ0ZRUVG5zFBQUBAXXnhhufTaln333TcOOuig6NChQxx44IFRp06drfZMmzYtOnfuHNOmTauwOQAAAAAAAAAAAIDKJ6wNAAAAsJvIzf3/v1WTcrv2yJEjM2HXLXvxzdKvX7+sMH+NGjXijjvuiOXLl8eMGTMiPz8/li9fHrfddltWaPujjz6Kc845p0JnW7lyZZxxxhmxbt26zFrz5s1jzJgxsWLFipg6dWrMmTMn5s6dGwMGDMg6O3r06Lj99tvLZY4tbxyvXbt2mXpVqVIlunTpEjfddFNMmjQpCgoKYtGiRfHuu+/Ga6+9Fu+9914UFBTEG2+8Eb179846u2LFijjjjDPiiy++KNMMAAAAAAAAAAAAwO7L/9oFAAAA2E106dIl8/qhhx4q9S3DWwa8f/CDH5TbXOw+nnvuuXjmmWcydbVq1eI///lPXHLJJVGrVq3Meu3ateN//ud/4tlnn41q1apl1v/973/HSy+9VGHz3XrrrbFo0aJM3bJly5g8eXJ069YtcnJyMuv7779/3HvvvXHzzTdnnb/xxhtj5cqVZZphwoQJ8fe//z0ivvqhBddff31yr1NOOSWWLFkSL774Ylx99dXRsWPHqFev3lb7cnNz48gjj4yHHnoohg8fnvXehx9+GA888EDyDAAAAAAAAAAAAMDuTVgbAAAAYDfRp0+fzOs5c+bEyy+/XOKzr776asyePXubvfjmuPbaa7Pq3/3ud9GpU6ft7u/cuXNcccUVWWvXXHNNhcy2bNmy+POf/5y1dt9990VeXt52z1x55ZVZ8xcUFMSf/vSn5BnWrVsX5557buYHHfz2t7+NI488Mrnf/vvvH3vttVepzvTt2zd69eqVtfb4448nzwAAAAAAAAAAAADs3oS1AQAAAHYTP/rRj2LvvffO1FvelL0zI0aMyLxu3Lhx/OhHPyrX2ah87733XrzxxhuZunbt2nHZZZft9Nzll18etWvXztSTJ0+OWbNmlft8jz76aKxZsyZTd+rUKX74wx/u8ExOTs5WN18/8MADpb5V/r+uvfba+PjjjyMiolmzZnHTTTcl9Smr3r17Z9UV8esNAAAAAAAAAAAA7B6qVvYAAAAAAHylWrVqcdZZZ8Wdd94ZEV/dxnv33XdHjRo1dnhu/fr18dhjj2Xqs846K6pWLb9v+3zwwQcxffr0WLZsWRQUFETDhg0jLy8vjj/++GjYsGGZeq9fvz7y8/Nj1qxZsWzZsigsLIy6devGXnvtFQcddFAceOCBkZtb/j9v8IMPPogpU6bEokWLokqVKtG4ceM46qij4oADDij3Z5WXJ598Mqvu2bNn1K1bd6fn6tatGz169Ijhw4dn1saMGVPun7X4fP379y/RuS5dukTLli1jzpw5ERHx2Wefxeuvvx7HHHNMqZ7/5ptvxh133JGp77nnnqhTp06pepSX1q1bZ9XLly8v1fl169bF9OnTIz8/P1auXBnr1q2LmjVrRr169aJFixbRtm3baNq0aXmODAAAAAAAAAAAACQS1gYAAADYjfTp0ycT1i4oKIgxY8ZEr169dnhmzJgxUVBQkNWjrNasWRNDhw6NESNGZEK0xVWpUiU6duwYN954Y3Ts2LHEvT/99NN49NFHY9y4cfHaa6/FF198sd29e+65Z5x99tkxcODAyMvLK1H/uXPnRsuWLTN13759M0Hl5557Lq6++up46623tnn2gAMOiMGDB8dpp51W4s+zq4wbNy6rPvnkk0t89qSTTsoKaz/11FNx5ZVXltdosWbNmpg0aVLWWknny8nJiRNPPDHuu+++rPlKE9beuHFj9O/fPzZt2hQRET169IhTTz21xOfL2/r167PqBg0alOjc7Nmz48Ybb4zRo0dHYWHhDvfm5eVF165d4/zzz48OHTqkjgoAAAAAAAAAAACUUflfSwQAAABAssMOOywOPPDATD1ixIidntlyz0EHHRSHHnpomWZ46qmnonXr1vH73/9+u0HtiIhNmzbFhAkTolOnTjFgwID48ssvd9r73XffjWbNmsVll10WEyZM2GFQOyJi5cqVcdttt0W7du3imWeeKfVn2dLll18eXbt23W5QOyJi1qxZcfrpp8cf/vCHEvft169f5OTkZL769etXpjm3paioKN59992stWOPPbbE54877risevr06VFUVFQus0VEzJw5MzZu3JipW7ZsGfvss0/yfNOmTSvV82+55ZZ47733IuKrYPRdd91VqvPlbcqUKVn14YcfvtMzDz30UBx44IHx0EMP7TSoHRGxaNGiePDBB+Puu+9OnhMAAAAAAAAAAAAoO2FtAAAAgN3Mljdjjx8/Pj777LPt7l28eHGMHz9+m2dTDBs2LLp37x5Lly7NWq9Vq1YccMABcdRRR0WbNm0iNzd3q3O/+MUvdhoA3rBhw1Z7qlevHq1bt45DDz00jjrqqPjOd74TVatWzdpTUFAQp556arz00ktJn+t3v/td3HrrrZm6bt260b59+zjiiCNi77333mr/ddddF6NHj056VkWYN29erF27NlPXrl07mjVrVuLzzZs3j1q1amXqwsLCWLBgQbnNN2vWrKy6Xbt2pTpffH/xfjuSn58fN998c6YePHhwqYLi5W3dunVx2223Za317dt3h2fGjx8fffv23eqHF9SqVSvatWsXHTp0iEMPPTRatGix1d89AAAAAAAAAAAAoHL5n30AAAAAu5nevXtHlSpVIuKr26sfeeSR7e59+OGHY9OmTRERUaVKlfjlL3+Z/NwXXnghLrzwwky/iIjTTjstJkyYEAUFBZGfnx9TpkyJjz76KJYtWxaDBw+OunXrZvY++eSTMWTIkBI9q3PnznH77bfHjBkzorCwMGbPnh1Tp06NKVOmxIcffhirV6+OMWPGxFFHHZU5s3nz5ujdu3esWbOmVJ9r0qRJMXjw4IiIOProo+O5556LFStWxIwZM+LNN9+MJUuWxEsvvRRt27bNOnfxxReX6LbwXeGDDz7Iqps2bVrqHsXPFO9ZFmWdr/j+efPmxfr163d6bvPmzdG/f//YsGFDRER07NgxzjvvvFI9uzwtXLgwfvKTn8SHH36YWTvhhBPijDPO2OG5Sy+9NOuHGHTp0iUmTJgQ/+///b+YOXNmvPbaazF16tSYM2dOrFmzJiZPnhzXXHNNtGrVqsI+CwAAAAAAAAAAAFAywtoAAAAAu5l99903TjrppEw9cuTI7e4dMWJE5vXJJ58c++67b9IzV61aFb17947NmzdHRERubm7cf//9MXbs2OjcufNWN103bNgwLr/88nj99dezbqa+7rrrdngTeLNmzWLGjBkxYcKEuPTSS6N9+/Zb9Y6IqFGjRnTr1i1ee+21OPfcczPrixYtioceeqhUn23OnDkREdGvX7949dVX46STTsp6Zk5OTpxwwgkxadKkyMvLy6wvXLgwxo0bV6pnVZTiN53vv//+pe6x33777bBnWZR1viZNmmT9nmzevDk+//zznZ6766674vXXX4+Ir25oHzZsWOTk5JTq2aXx5ZdfxvPPP5/1NWbMmLj77rujV69e8Z3vfCfr9vcOHTrE6NGjdzhTfn5+5OfnZ+ouXbrE888/H507d8780IYt1axZM4455pj4wx/+EB999FFcd9115fshAQAAAAAAAAAAgFIR1gYAAADYDfXp0yfz+t13341p06Ztteftt9+OmTNnbvNMad17771ZIeubb745zjnnnJ2ea9euXQwfPjxTb9iwIe6+++7t7m/cuHG0b9++xHPl5ubGPffcE61bt86sPfjggyU+/19HHHFEDBs2bJvh1//ae++949prr81ae+aZZ0r9rIpQ/Dbx2rVrl7pH8TOlvaF8R8o6X05OTtSsWXOHPYubM2dOXHPNNZn6yiuv3Op29PK2Zs2aOOmkk7K+fvrTn8Zvf/vb+Oc//xnr1q2LiK/C50OGDIlJkybFnnvuucOeW97CHRExYMCAyM0t2bdtc3Nz47vf/W7ahwEAAAAAAAAAAADKhbA2AAAAwG6oe/fuUa9evUy9rdu1t7xVu379+tG9e/ekZ23atCn+/Oc/Z+pmzZrFwIEDS3z+xz/+cRx66KGZ+l//+lfSHNtTvXr16NGjR6Z+5513MqHYkrrxxhujWrVqO93Xs2fPrHrq1Kk7PTN8+PAoKirKfG0ZXi8vxYPLNWrUKHWP0oahS6My5jv//POjsLAwIiLatm0bV111VamfWRGaNGkSV199dZx33nkl+jNX/M9ySc4AAAAAAAAAAAAAuw9hbQAAAIDdUM2aNbOCw//7v/8bmzZtytQbN26Mf/zjH5m6Z8+eSQHZiIjp06fHokWLMnWvXr1KHRg9+eSTM6/ff//9WL58edIs29OyZcvM6y+//DJmzJhR4rP169ePrl27lmhvw4YNo1mzZpl6wYIFJR+yAq1fvz6rrl69eql77LHHHll1aQPvO7Kr57v//vvj+eefj4ivbuUeNmxY0jMrwpIlS+Liiy+OZs2axdChQ6OoqGiH+/Py8rLqRx55pCLHAwAAAAAAAAAAAMqZsDYAAADAbqpPnz6Z10uWLIn//Oc/mXrcuHFZgegt95bWyy+/nFUfccQRpe6xZcA5ImLWrFk7PbN27dp49NFHY8CAAdGhQ4fIy8uLunXrRm5ubuTk5GR9DRgwIOtsacLghx12WOTmlvzbYI0bN868LigoKPG5ilQ8iL9hw4ZS9/jiiy922LMsduV8ixcvjkGDBmXqc889Nzp27Fjq56Vo0KBB1i3qmzZtihUrVsTUqVPjrrvuioMOOiizd/Xq1TFo0KDo27dvbN68ebs9jz766KhXr16mHj16dPTs2TPee++9Cv0sAAAAAAAAAAAAQPkQ1gYAAADYTR1//PHRqlWrTD1ixIhtvm7dunUcf/zxyc8pHqzu2bPnVmHpnX39+te/zuqxYsWK7T5v48aNMXjw4Nhnn33izDPPjGHDhsWUKVNi8eLFsWbNmp3eRBwRsWrVqhJ/vi3D1yVRu3btzOvyvH26LOrUqZNVF7/JuiSKf5biPctiV87361//OvP7v88++8SQIUNK/azykpubG3vuuWcceuih8dvf/jamT58ef/rTnyInJyez56GHHoqhQ4dut0eNGjXiiiuuyFobNWpUHHzwwdGuXbu49NJL44knnojPPvuswj4HAAAAAAAAAAAAkE5YGwAAAGA3lZOTE7/61a8y9dixY6OgoCCWL18e48aNy6xvuSfF559/Xqbz27K9G6nXrVsXp5xySvzud7+L1atXJ/cvfgvzjpTnDdKVpXhwubCwsNQ9ip+pyLB2aecrKioqUVh71KhR8cQTT2TqO++8Mxo0aFCqZ1WknJycGDhwYNxyyy1Z6zfccEOsXLlyu+euvPLKOP/887danzVrVtx5553xs5/9LPbdd99o27ZtXHLJJTFlypRynx0AAAAAAAAAAABII6wNAAAAsBvr06dP5pbe9evXx2OPPRb/+Mc/YuPGjRHxVTi0T58+ZXpGaW6pLqnNmzdvc/2iiy6KF198MWtt7733jh49esRNN90UI0aMiCeeeCKeffbZGD9+fObrsssuK/cZv06K3w7+6aeflrrHwoULd9izLMo635IlS+LLL7/M1Lm5udGoUaOt9m355+AnP/lJ9OzZs5ST7hoDBw6MVq1aZerCwsJ4/PHHt7s/Jycn/va3v8Wzzz4bxx9//Hb3ffDBB3HXXXdFhw4d4vjjj4+33nqrXOcGAAAAAAAAAAAASq9qZQ8AAAAAwPa1atUqjj/++Hj55ZcjImLkyJFZNxB37NgxWrZsWaZn1KpVK6v+4x//GIcffniZerZv336rtWnTpsWIESMydbVq1WLIkCFx0UUXRfXq1XfY7+OPPy7TPF933/ve97LqBQsWlLpH8TNt27Yt00xbKj7f/PnzS3W++P7mzZtv80b0LX+wwLhx4zI/yKA05s2bt9W5d955Jw455JBS99qeqlWrxumnnx533HFHZm3y5Mlx3nnn7fBc165do2vXrjFnzpx47rnnYsKECTFp0qRYtGjRVntfffXVOO644+Lhhx+OHj16lNvsAAAAAAAAAAAAQOkIawMAAADs5vr06ZMJa7/yyitbvVdWxW8wbtmyZZx44oll7lvcY489FkVFRZn6hhtuiEsvvbREZ1esWFHu83ydNG/ePGrWrJkJ6hcWFsa8efOiefPmJTo/b968WLt2baauXbt2NG3atNzmKx78zs/PL9X5WbNm7bDf11Hr1q2z6s8++6zEZ1u2bBkDBgyIAQMGRETEJ598Ei+88EKMHj06nnvuuczN9Rs2bIg+ffrE0UcfHc2aNSu/4QEAAAAAAAAAAIASy63sAQAAAADYsZ49e0bNmjW3Wq9Zs2a53Khb/Gbu2bNnl7nntrz++uuZ17m5uXHBBReU+OzMmTMrYqSvjZycnDj44IOz1iZPnlzi86+++mpWffDBByfdSr097du3j2rVqmXquXPnxuLFi5PnK89brncXW/76lFarVq3ivPPOi2eeeSamT58erVq1yry3fv36uOeee8pjRAAAAAAAAAAAACCBm7UBAAAAdnP16tWLbt26xaOPPpq13r1796hXr16Z+3fp0iWrfvHFF+Oqq64qc9/ilixZknm99957x5577lmic5s3b46JEyeW+zxfN6eeempMmTIlU48fPz7OPPPMEp0dP358Vn3aaaeV62x169aNTp06xQsvvJD1zJLc/F5UVBTPP/98ieZ78sknY+PGjaWabfr06TFo0KBM3aRJk3j44Yez9rRp06ZUPUti3rx5WXWTJk3Kpe+BBx4Yw4YNixNPPDGz9sorr5RLbwAAAAAAAAAAAKD0hLUBAAAAvgb69u27VVi7b9++5dL7qKOOij333DNWrlwZEV+FtfPz86Ndu3bl0v+/ioqKMq83bNhQ4nNjx46NTz/9tFxn+To6/fTT49prr83Uo0aNirvuuivq1Kmzw3OrV6+OUaNGZa1169atQubbMqx9//33lyis/dJLL8WcOXMydZMmTeLoo4/e5t7OnTuXeq6qVbO/BVqjRo2soHNFKCoqiqeeeiprrfjN6GVx3HHHZdXLly8vt94AAAAAAAAAAABA6eRW9gAAAAAA7FzXrl1j9erVWV8nn3xyufSuVq1aXHrppZm6qKgoBgwYUOobjHdmn332ybxeuXJl5Ofn7/TMmjVrYuDAgeU6x9fVwQcfHEceeWSmXrNmTQwZMmSn54YMGRKFhYWZukOHDuUexI+I6NWrV9SuXTtTT5o0KV588cUdnikqKoobbrgha+3ss8+O3Nyv97ctH3zwwXj//fez1k4//fRy6188nF3SW+oBAAAAAAAAAACA8vf1/l+PAAAAAN8SOTk5UadOnayvnJyccut/ySWXRJMmTTL1K6+8Er/4xS+ioKCgxD0KCwvjrrvuivvvv3+b7x977LFZ9eWXXx6bN2/ebr+1a9fGz372s/jkk09KPENl6NevX+Tk5GS++vXrV2HPuvHGG7PqP/7xjzFp0qTt7p84cWIMHjw4a+2mm27a6XMmTJiQ9ZlK8metcePG8Zvf/CZr7dxzz41FixZt98wtt9ySNX/9+vXjsssu2+mzdoWJEyfGkCFDYu3ataU6N2rUqLjwwguz1nr06BHNmzff5v4777wz7rnnnlI959Zbb82qDz/88FLNCAAAAAAAAAAAAJQfYW0AAAAAon79+jFq1KioVq1aZm3s2LHRvn37GDp0aMyfP3+b5xYsWBCPP/549O7dO/Ly8uKSSy6JBQsWbHNv7969s25MHjduXJx22mlb3bC9fv36ePzxx+P73/9+jB8/PiIiDjjggLJ+xG+EU045JetG9Y0bN0bXrl3jzjvvzAr7FhYWxh133BGnnHJK1g3pP/7xj+OHP/xhhc13+eWXZ92gPmfOnDj22GNj7NixUVRUlFn/9NNP44ILLoirr7466/zVV18dDRs2rLD5SmPlypVxxRVXxH777Rf9+/ePp556KpYsWbLNvatXr46xY8fGT37yk+jZs2ds2LAh817Dhg1j6NCh233OnDlz4je/+U3k5eVF375944knnojFixdvc++0adOiV69ecdddd2XWcnNz45xzzkn8lAAAAAAAAAAAAEBZVa3sAQAAAADYPXTs2DFGjhwZZ599dqxfvz4iIhYuXBiDBg2KQYMGxb777huNGzeOPfbYIwoKCmLp0qWxcuXKEvdv27ZtXHDBBfGXv/wls/b000/H008/HU2bNo1999031qxZE3Pnzs0KHnfq1Cl+9atfxXnnnVd+H/ZrbOTIkXHMMcfEnDlzIuKrcPull14aV155ZbRq1SqKiorik08+yfwe/lfr1q1j+PDhFTpbw4YN45///Gd07do18/x58+ZFt27dokGDBtGyZctYtWpVzJ8/PzZt2pR1tlu3bjFo0KAKnS/FqlWr4oEHHogHHnggIiL23nvvaNSoUdSrVy82bNgQK1asiPnz52eF0f+rQYMGMX78+GjatOlOn1NQUBAjR46MkSNHZp7TuHHjqFu3bqxfvz7mzp0bq1at2urc5Zdf7mZtAAAAAAAAAAAAqETC2gAAAABk9OrVK77zne/EWWedFR9++GHWe4sXL97ujb//VaVKlcjLy9vu+7fffnvMnz8/nnrqqaz1BQsWbPNG7i5dusTo0aNjzJgxJf8Q33BNmjSJl156Kbp16xbTp0/PrK9bty5mzpy5zTOHHHJIjB07Nvbee+8Kn69Tp04xbty46NGjR6xYsSKzvmrVqnjnnXe2eeass86KBx54IHJycip8vrJatmxZLFu2bKf7TjrppPjb3/4WLVu2rJDnVKlSJa6++uq44YYbkvoDAAAAAAAAAAAA5SO3sgcAAAAAYPdy+OGHR35+fowcOTI6dOgQVapU2eH+PfbYI37wgx/En/70p1iwYEGcf/75291bvXr1ePLJJ+P222+PffbZZ7v7WrRoEXfffXc8//zz0aBBg9SP8o3VvHnzeOONN2Lw4ME7DMfn5eXFkCFDYsqUKSW63bm8/OAHP4j8/Py48MILo1atWtvdd+ihh8a//vWveOSRR2KPPfbYZfOVxMknnxyjR4+O8847L773ve+VKEher169OOuss+KFF16I5557rkRB7RtvvDEeffTR6N27d4l+j+rUqRO9e/eOd955R1AbAAAAAAAAAAAAdgM5RUVFRZU9BOwOZs6cGQceeGCmnjFjRrRv374SJwIAAKBMZs6M2OLfeds0Y0aEf/vtVEFBQbz++uuxaNGiWL58eWzcuDHq1q0bjRs3jrZt28b3vve9qFGjRqn7fvnll/Hmm2/Gu+++G59//nlUqVIl9tlnnzjkkEPi+9//fgV8km+mzZs3x9tvvx3Tp0+PpUuXRkRE48aN45BDDonDDjsscnMr9+c1rlu3LiZPnhyzZs2KVatWRfXq1WO//faLo48+Otq0aVOps5XGqlWrIj8/P+bMmRNLly6NwsLCqF69etSvXz/22muvOOigg+K73/1umW8HX7hwYbz//vsxZ86cWLlyZXzxxRdRq1at2GuvvaJ9+/Zx0EEH7XbBdgAAAAAAAAAAAKhMlZ0PFdaG/1PZfxkBAAAoZ8LaAAAAAAAAAAAAAPCNV9n50Mq9VgcAAAAAAAAAAAAAAAAAAOBrSlgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJKha2QMAAHzdtPjduMoegTKa+8efVPYIAAAAAAAAAAAAAAAAfAO4WRsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQoGplD8A318cffxxvvPFGfPrpp7Fhw4bYc889o23btnHsscdGjRo1Kns8AAAAAAAAAAAAAAAAAAAoE2HtSrZw4cJ44403YsqUKfHGG2/EW2+9FatXr86837x585g7d26FPf+9996Lww8/PDZu3Ji1/uCDD0a/fv2Seo4ZMyb+8Ic/xNSpU7f5fp06daJfv35x/fXXR6NGjZKeAQAAAAAAAAAAAAAAAAAAlU1YuxK8+uqrMXTo0JgyZUosWrSo0ubYtGlT9O/ff6ugdqovvvgi+vfvH4888sgO961Zsybuvvvu+Oc//xmPP/54dOrUqVyeDwAAAAAAAAAAAAAAAAAAu1JuZQ/wbfTmm2/GE088UalB7YiI22+/Pd58881y6bV58+Y444wztgpqV6lSJVq2bBmHHHJI1K9fP+u9ZcuWxY9+9KN47bXXymUGAAAAAAAAAAAAAAAAAADYlYS1dzN16tTZJc/5+OOP47rrrsvUtWvXLlO/W2+9NZ588smstQsuuCDmz58fn3zySbzzzjuxYsWKGD16dDRr1iyzZ+3atdGzZ88oKCgo0/MBAAAAAAAAAAAAAAAAAGBXE9auRHXr1o0TTjghLrvsshg1alTMnTs3/v3vf1f4c4uKiuK8886LdevWRUTEaaedFkcccURyv88//zxuvvnmrLVbbrkl/vrXv0ZeXl5mLTc3N37605/G5MmTo0WLFpn1Tz/9NG677bbk5wMAAAAAAAAAAAAAAAAAQGUQ1q4Ep512WsycOTNWrVoVL730UgwZMiR+8YtfRPPmzXfJ8++777546aWXIuKrm7zvueeeMvUbMmRIrF69OlN36tQprrjiiu3u32+//eLvf/971trtt98en3/+eZnmAAAAAAAAAAAAAAAAAACAXUlYuxK0bt062rVrF7m5u/6Xf+HChXH55Zdn6ptvvjmaNm2a3G/z5s3x4IMPZq39/ve/j5ycnB2e++EPfxgdO3bM1KtXr47HHnsseQ4AAAAAAAAAAAAAAAAAANjVhLW/ZS666KIoKCiIiIijjjoqfvOb35Sp3+TJk2PZsmWZulWrVnHCCSeU6Gz//v2z6jFjxpRpFgAAAAAAAAAAAAAAAAAA2JWEtb9FHn300Rg7dmxERFStWjXuu+++Mt/uPW7cuKz6pJNO2umt2lvu3dKECROisLCwTPMAAAAAAAAAAAAAAAAAAMCuIqz9LfH555/HxRdfnKkHDhwYBx98cJn7Tps2Las+9thjS3w2Ly8vWrRokak3bNgQ+fn5ZZ4JAAAAAAAAAAAAAAAAAAB2BWHtb4lLLrkkli1bFhERrVu3juuvv75c+s6aNSurbteuXanOF99fvB8AAAAAAAAAAAAAAAAAAOyuhLW/BZ5++ul45JFHMvW9994bNWvWLHPfdevWxfz587PWmjZtWqoexfd/8MEHZZ4LAAAAAAAAAAAAAAAAAAB2haqVPQAVa/Xq1XHBBRdk6l/96ldx4oknlkvv5cuXR1FRUaauVq1aNG7cuFQ99ttvv6x66dKl5TLb0qVLMzeJl9Ts2bPL5dkAAAAAAAAAAAAAAAAAAHw7CGt/w11xxRWxYMGCiIho1KhR3HbbbeXWe82aNVl1rVq1Iicnp1Q9ateuvcOeqf7yl7/EDTfcUC69AAAAAAAAAAAAAAAAAABgW3IrewAqzssvvxz33ntvph46dGg0atSo3PoXD1bXqFGj1D1q1qy5w54AAAAAAAAAAAAAAAAAALC7Etb+hlq/fn30798/ioqKIiLixBNPjD59+pT7M7ZUvXr1UvfYY489sup169aVaSYAAAAAAAAAAAAAAAAAANhVqlb2AFSM66+/Pj766KOI+Or26i1v2C4vxW/S3rBhQ6l7fPHFFzvsmeqiiy6KHj16lOrM7Nmzo3v37uXyfAAAAAAAAAAAAAAAAAAAvvmEtb+Bpk6dGkOHDs3U1113XbRu3brcn1OnTp2suvhN2yVR/Cbt4j1TNW7cOBo3blwuvQAAAAAAAAAAAAAAAAAAYFtyK3sAyteXX34Z55xzTmzatCkiIg4++OAYNGhQhTyreLB67dq1UVRUVKoehYWFO+wJAAAAAAAAAAAAAAAAAAC7K2Htb5iHH344pk+fHhERubm5MWzYsKhatWIuUG/UqFHk5ORk6o0bN8bSpUtL1WPhwoVZtduwAQAAAAAAAAAAAAAAAAD4uhDW/oZZtWpV5vXmzZujQ4cOkZOTs9OviRMnZvU5++yzs97v3r37Vs+qWbNmNGvWLGtt/vz5pZq3+P62bduW6jwAAAAAAAAAAAAAAAAAAFQWYW3KpHi4Oj8/v1TnZ82atcN+AAAAAAAAAAAAAAAAAACwuxLWpkwOOeSQrHry5MklPrt48eKYO3dupq5WrVq0a9eunCYDAAAAAAAAAAAAAAAAAICKVbWyB6B8/fznP48DDzyw1OcGDhwY7777bqa+7LLL4uSTT87UjRs33ua5U089NQYPHpypn3/++SgqKoqcnJydPvO5557Lqrt06RJ16tQp7egAAAAAAAAAAAAAAAAAAFAphLW/YZo2bRpNmzYt9bk999wzq27Xrl2ceOKJOz137LHHRqNGjWL58uUREfHJJ5/EhAkTokuXLjs9e//992fV3bp1K8XEAAAAAAAAAAAAAAAAAABQuXIrewC+3nJzc6Nfv35ZazfccEMUFRXt8NwLL7wQL7/8cqauW7du9OzZsyJGBAAAAAAAAAAAAAAAAACACiGsTZldccUVUadOnUw9ceLEGDx48Hb3L1y4MM4999ystUsuuSQaNWpUYTMCAAAAAAAAAAAAAAAAAEB5q1rZA3xbvfrqq7Fu3bqt1qdPn55Vr1+/Pp5//vlt9sjLy4t27dpVyHyl0ahRo7jqqqviqquuyqxdeeWVMX/+/LjmmmsiLy8vIiI2b94cY8eOjUsuuSTmz5+f2ZuXlxcDBw7c5XMDAAAAAAAAAAAAAAAAAEBZCGtXkl/+8pcxb968ne5bsmRJnHTSSdt8r2/fvjF8+PBynizNFVdcEZMnT46nnnoqs/bXv/41hg0bFs2bN4/69evHnDlzYtWqVVnnatasGY899lg0aNBg1w4MAAAAAAAAAAAAAAAAAABllFvZA/DNkJubG6NGjYpevXplrW/atCk++eSTeOedd7YKau+1117x9NNPx3HHHbcLJwUAAAAAAAAAAAAAAAAAgPIhrE25qVGjRvzjH/+Ixx9/PA455JDt7qtdu3ZcdNFFkZ+fHyeccMIumw8AAAAAAAAAAAAAAAAAAMpT1coe4Ntq7ty5lT1ClgkTJpRbr5///Ofx85//PGbPnh1TpkyJhQsXxoYNG6JBgwZxwAEHxHHHHRc1atQot+cBAAAAAAAAAAAAAAAAAEBlENamwrRp0ybatGlT2WMAAAAAAAAAAAAAAAAAAECFyK3sAQAAAAAAAAAAAAAAAAAAAL6OhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAAAAAAAAAAAAAAEACYW0AAAAAAAAAAAAAAAAAAIAEwtoAAAAAAAAAAAAAAAAAAAAJhLUBAAAAAAAAAAAAAAAAAAASCGsDAAAAAAAAAAAAAAAAAAAkENYGAAAAAAAAAAAAAAAAAABIIKwNAAAAAAAAAAAAAAAAAACQQFgbAAAAAAAAAAAAAAAAAAAggbA2AAAAAAAAAAAAAAAAAABAAmFtAAAAAAAAAAAAAAAAAACABMLaAAAAAAAAAAAAAAAAAAAACYS1AQAAAAAAAAAAAAAAAAAAEghrAwAAAAAAAAAAAAAAAAAAJBDWBgAAAAAAAAAAAAAAAAAASCCsDQAAAAAAAAAAAAAAAAAAkEBYGwAAAAAAAAAAAAAAAAAAIIGwNgAAAAAAAAAAAAAAAAAAQAJhbQAAAAAAAAAAAAAAAAAAgATC2gAAAAAAAAAAAAAAAAAAAAmEtQEAAAAAAAAAAAAAAAAAABIIawMAAAAAAAAAAAAAAAAAACQQ1gYAAAAAAAAAAAAAAAAAAEggrA0AAAAAAAAAAAAAAAAAAJBAWBsAAAAAAAAAAAAAAAAAACCBsDYAAAAAwP/H3p0HeV3XDxx/7QrL6XCGhccCOmiLFo5NNDgSHiiaiGWiZnlMVmbOeOQRmiN4jldO1miemKV5FOJBk4FJKhikYhqHDi4LA6IsKA4oy7X7++/767tc+3258EV4PP57v7/vaxn+fc4HAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACChTbkfwPaxatWqmDVrVsydOzeWL18eDQ0N0bVr1+jVq1d87Wtfiz59+rT6nbNmzYrXXnstlixZEhs2bIgePXrEgQceGIMGDYo2bfzXAwAAAAAAAAAAAAAAAADg800xW2aLFy+OGTNmxPTp02PGjBnx6quvxsqVKwu/V1dXR11dXers6dOnx4QJE+L555+P1157LRobGze7trq6Os4999z4yU9+Et26dUvdFxHR1NQU48aNi5tuuineeeedTa7p0aNH/PSnP41f/OIX0alTp/RdAAAAAAAAAAAAAAAAAABQTmLtMpg6dWrcdtttMX369Hjvvfda/fw33ngjTjrppKitrW3xngULFsTo0aPj17/+dYwbNy6GDx9e8r0rVqyIUaNGxaRJk7a4bvny5XHdddfFI488Ek8//XQMGDCg5LsAAAAAAAAAAAAAAAAAAKDcKsv9gF3Rv//973jyySe3SagdEbFo0aLNhtpdunSJ/fffP77+9a9Hv379oqKiouj3999/P771rW/Fo48+WtKdq1evjmOOOWajULuqqir69+8fBx100EZf0a6trY3DDz885s2bV9JdAAAAAAAAAAAAAAAAAACwIxBr72A6d+7c6md+4xvfiN/+9rcxa9asWLFiRcydOzemT58e7777bnzwwQdx/fXXR8eOHQvrGxsb44wzzoiZM2e2+I6LL744ZsyYURhXVlbGVVddFe+//368/fbb8eabb8aHH34Y48aNi27duhXW1dfXx6hRo2LDhg2t88cCAAAAAAAAAAAAAAAAAMB2ItYuo9133z2GDh0al156aTzxxBNRV1cXzzzzTKucXVlZGd///vfjv//9b7zyyivxs5/9LGpqajZa94UvfCGuuOKKeOWVV6J79+6F+XXr1sWFF17Yorvmzp0b9957b9HcH//4x7jmmmuKwuyqqqo466yz4qWXXoquXbsW5mfOnBkPPfRQaX8gAAAAAAAAAAAAAAAAAACUmVi7DEaMGFH4yvULL7wQN998c3z3u9+N6urqVjm/f//+8eabb8Yf/vCHGDBgQIv2fOUrX4lx48YVzb344osxb968re69+uqri76M/YMf/CBOO+20za4fMGBA3HrrrUVzY8eOjXXr1rXorQAAAAAAAAAAAAAAAAAAsCMQa5fBvvvuGzU1NVFZuW3++fv379/iSPt/nXDCCRt9fftvf/vbFvd89NFHMX78+MK4oqIixowZs9W7zj777KI4fcGCBTF58uTSHgwAAAAAAAAAAAAAAAAAAGUk1qbIYYcdVjReuHDhFtdPnDgx1q9fXxgPHTo0+vXrt9V7Kisr4+yzzy6amzBhQssfCgAAAAAAAAAAAAAAAAAAZSbWpki3bt2Kxh9//PEW10+cOLFofPTRR7f4rmHDhhWNn3322RbvBQAAAAAAAAAAAAAAAACAchNrU2Tx4sVF4x49emxx/RtvvFE0Hjx4cIvvOuSQQ6Jdu3aF8XvvvRf19fUt3g8AAAAAAAAAAAAAAAAAAOUk1qagqakpXn755aK5/v37b3b9unXrYt68eUVzNTU1Lb6vXbt2se+++xbNzZkzp8X7AQAAAAAAAAAAAAAAAACgnMTaFEyZMiXmz59fGFdUVMTw4cM3u762tjbWr19fGHfo0CF69uxZ0p1777130fjtt98uaT8AAAAAAAAAAAAAAAAAAJSLWJuIiGhsbIzRo0cXzQ0fPjy++MUvbnbP0qVLi8Z77rlnyfc239P8TAAAAAAAAAAAAAAAAAAA2FG1KfcD2DHceuutMX369MK4srIyrr/++i3uWbVqVdG4U6dOJd/bfE/zM7OWLl0a9fX1Je2ZN29eq9wNAAAAAAAAAAAAAAAAAMCuQaxNvPTSS3HllVcWzV144YVx8MEHb3Ff87C6ffv2Jd/doUOHLZ6Zdeedd8bYsWNb5SwAAAAAAAAAAAAAAAAAANiUynI/gPKqra2N73znO7F+/frC3MCBA+OGG27Y6t6GhoaicVVVVcn3t2vXrmi8evXqks8AAAAAAAAAAAAAAAAAAIByEGvvwpYtWxbHHntsLFu2rDC3xx57xPjx4zeKqDel+Ze0165dW/Ib1qxZs8UzAQAAAAAAAAAAAAAAAABgR9Wm3A+gPFauXBnHHntsvPPOO4W5Ll26xHPPPRd9+/Zt0RmdO3cuGjf/0nZLNP+SdvMzs84777w4+eSTS9ozb968OPHEE1vlfgAAAAAAAAAAAAAAAAAAdn5i7V1QQ0NDnHDCCfHqq68W5jp27BgTJ06Mr371qy0+p3lY/cknn5T8luZ7WivW7tWrV/Tq1atVzgIAAAAAAAAAAAAAAAAAgE2pLPcD2L7WrVsXo0aNiilTphTmqqqqYvz48XHooYeWdFbzGHrx4sUlv6f5HoE1AAAAAAAAAAAAAAAAAACfF2LtXUhjY2OcccYZ8cwzzxTmdtttt3jkkUfimGOOKfm8fv36RZs2//9x9tWrV0d9fX1JZyxcuLBofMABB5T8DgAAAAAAAAAAAAAAAAAAKAex9i6iqakpfvzjH8ejjz5amKuoqIj77rsvTjrppNSZbdu2jX333bdobvbs2S3ev2bNmqitrS2aE2sDAAAAAAAAAAAAAAAAAPB5IdbeRVx00UVx//33F83dcccdcdZZZ32mcwcOHFg0njZtWov3vvbaa7FmzZrC+Etf+lL06tXrM70HAAAAAAAAAAAAAAAAAAC2F7H2LuCqq66KX//610VzN9xwQ5x//vmf+ezjjz++aDxp0qQW722+dsSIEZ/5PQAAAAAAAAAAAAAAAAAAsL2ItXdyt9xyS1x33XVFc6NHj47Ro0e3yvnHHXdctGnTpjCeMmVK1NbWbnVfU1NTPPjgg0VzI0eObJU3AQAAAAAAAAAAAAAAAADA9iDW3ondfffdcdlllxXNnX/++XHDDTe02h3du3ePE088sTBuamqKMWPGbHXfAw88EHV1dYVxdXV1HHXUUa32LgAAAAAAAAAAAAAAAAAA2NbE2jupRx55JM4777yiubPPPjvuuOOOVr9r7NixUVn5//+V/vCHP8Sf/vSnza6fPXt2XHLJJUVzV111VVRVVbX62wAAAAAAAAAAAAAAAAAAYFtpU+4H7KqmTp0aq1ev3mj+P//5T9G4oaEhJk+evMkzevfuHTU1NRvNT548Oc4888xobGwszB1wwAFxyimnxPPPP1/SO7t16xaHHHLIFtfU1NTEOeecE/fcc09h7vvf/37MmTMnLrrooujWrVtERKxbty4efvjhuPjii2PFihWFtV/5ylfizDPPLOldAAAAAAAAAAAAAAAAAABQbmLtMjn99NNjwYIFW133wQcfxLBhwzb525lnnhkPPvjgRvMvv/xyrF+/vmhu7ty5MXz48JLf+c1vfjOmTJmy1XW33357vP766/Hqq69GRERjY2Nce+21cdNNN0Xfvn2jXbt2UVtbG6tWrSra17Nnz3jiiSeiTRv/FQEAAAAAAAAAAAAAAAAA+HypLPcD2Dl07NgxnnvuuTjiiCOK5teuXRtvv/12vPnmmxuF2n369Il//OMf0b9//+35VAAAAAAAAAAAAAAAAAAAaBVibVpN9+7dY9KkSXHPPffEfvvtt8V1V1xxRbz11ltx0EEHbccXAgAAAAAAAAAAAAAAAABA62lT7gfsqurq6rbZ2WPGjIkxY8Zss/O3pLKyMn70ox/Fj370o3jrrbfi9ddfjyVLlsSGDRuiR48eceCBB8agQYOibdu2ZXkfAAAAAAAAAAAAAAAAAAC0FrE228xBBx3ky9kAAAAAAAAAAAAAAAAAAOy0Ksv9AAAAAAAAAAAAAAAAAAAAgM8jsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAltyv0AANjV9PnFxHI/AQAAAAAAAAAAAAAAAIBW4MvaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAktCn3A9i+GhoaYtq0aTF37tz46KOPoqqqKvbaa68YNGhQ9OvXr1Xvevfdd2PGjBmxaNGiWLt2bXTr1i0OOOCAGDx4cLRv375V7wIAAAAAAAAAAAAAAAAAgO1NrF1mixcvjhkzZsT06dNjxowZ8eqrr8bKlSsLv1dXV0ddXd1nvqe+vj7Gjh0bDz74YHzyySebXHPIIYfEVVddFSNHjvxMd02YMCGuvfbaeP311zf5e+fOneOss86Kq6++Onr27PmZ7gIAAAAAAAAAAAAAAAAAgHIRa5fB1KlT47bbbovp06fHe++9t83vmzJlSpx88smxbNmyLa577bXX4sQTT4wzzjgj7r333qiqqirpnjVr1sQPf/jDePjhh7e4btWqVfHb3/42Hnvssfjzn/8cQ4YMKekeAAAAAAAAAAAAAAAAAADYEVSW+wG7on//+9/x5JNPbpdQ++WXX47jjjtuo1C7a9eucfDBB0efPn1it912K/rtoYceitNOOy2amppafE9jY2OccsopG4Xau+22W/Tt2zcGDhwYXbp0Kfqtvr4+jj322HjllVdK/KsAAAAAAAAAAAAAAAAAAKD8xNo7mM6dO7faWR999FGccsopsXr16sJcdXV1TJgwIT788MN4/fXXY/78+VFXVxc/+clPivaOHz8+br/99hbfdcstt8RTTz1VNHfuuefGwoULo7a2NmbOnBkffvhhjB8/PvbZZ5/Cmk8//TRGjRoVH3/8cfKvBAAAAAAAAAAAAAAAAACA8hBrl9Huu+8eQ4cOjUsvvTSeeOKJqKuri2eeeabVzr/llluKvt7dt2/fmDZtWowcOTIqKioK83vttVf87ne/i+uvv75o/zXXXBMfffTRVu9Zvnz5RntvvPHGuOuuu6J3796FucrKyvj2t78d06ZNiz59+hTmFy1aFL/61a9K/fMAAAAAAAAAAAAAAAAAAKCsxNplMGLEiJg1a1asWLEiXnjhhbj55pvju9/9blRXV7faHfX19fGb3/ymaO7ee+8tiqebGz16dAwZMqQw/vjjj+PWW2/d6l0333xzrFy5sjAeMmRIXH755Ztdv+eee8Z9991XNHf77bfH8uXLt3oXAAAAAAAAAAAAAAAAAADsKMTaZbDvvvtGTU1NVFZuu3/+Rx99NFatWlUYDxkyJI488sgt7qmoqIirr766aO6BBx6Ipqamze5pbGyMcePGFc2NGTOm6Mvdm3LkkUfGYYcdVhivXLkyHn/88S3uAQAAAAAAAAAAAAAAAACAHYlYeyf11FNPFY1/+MMftmjf4YcfHn379i2M33///fjXv/612fXTpk2L+vr6wrhfv34xdOjQFt3V/E0TJkxo0T4AAAAAAAAAAAAAAAAAANgRiLV3QqtWrYoXX3yxaO7oo49u0d6Kioo46qijiuaeffbZza6fOHFi0XjYsGFb/ar2/679X1OmTIlPPvmkRXsBAAAAAAAAAAAAAAAAAKDcxNo7oVmzZsW6desK4759+8YXv/jFFu8/9NBDi8ZvvPHGZtc2/23w4MEtvqd3797Rp0+fwnjt2rUxe/bsFu8HAAAAAAAAAAAAAAAAAIByEmvvhObMmVM0rqmpKWl/8/XNzyvXXQAAAAAAAAAAAAAAAAAAsCMRa++E3n777aLx3nvvXdL+5usXLFgQDQ0NG61bvXp1LFy4sFXvav52AAAAAAAAAAAAAAAAAADYUbUp9wNofUuXLi0a77XXXiXt32OPPaJNmzaxfv36iIhobGyM5cuXx5577lm0btmyZdHU1FQYt23bNnr16lXSXc3PbP72rKVLl0Z9fX1Je+bNm9cqdwMAAAAAAAAAAAAAAAAAsGsQa++EVq1aVTTu1KlTSfsrKiqiQ4cOsXLlys2euam5jh07RkVFRUl3NX/bpu7JuPPOO2Ps2LGtchYAAAAAAAAAAAAAAAAAAGxKZbkfQOtrHjy3b9++5DM6dOiwxTO35z0AAAAAAAAAAAAAAAAAALAjEmvvhBoaGorGVVVVJZ/Rrl27ovHq1avLdg8AAAAAAAAAAAAAAAAAAOyI2pT7AbS+5l+4Xrt2bclnrFmzZotnbs97Ms4777w4+eSTS9ozb968OPHEE1vlfgAAAAAAAAAAAAAAAAAAdn5i7Z1Q586di8bNv4DdEs2/cN38zO15T0avXr2iV69erXIWAAAAAAAAAAAAAAAAAABsSmW5H0Drax48f/LJJyXtb2pqSsXan376aTQ1NZV0V/O3tVasDQAAAAAAAAAAAAAAAAAA25pYeyfU/IvSixYtKmn/Bx98EOvXry+MKysro2fPnhut69mzZ1RUVBTG69ati6VLl5Z01+LFi4vGvoYNAAAAAAAAAAAAAAAAAMDnhVh7J7T//vsXjRcuXFjS/ubrq6uro3379hut69ChQ+yzzz6tetcBBxxQ0n4AAAAAAAAAAAAAAAAAACgXsfZOqHnwPHv27JL2z5kzZ4vnlesuAAAAAAAAAAAAAAAAAADYkYi1d0IDBgyItm3bFsZ1dXWxZMmSFu+fOnVq0XjgwIGbXdv8t2nTprX4niVLlkRdXV1h3LZt26ipqWnxfgAAAAAAAAAAAAAAAAAAKCex9k5o9913jyFDhhTNTZo0qUV7m5qaYvLkyUVzI0aM2Oz6448/vmg8efLkaGpqatFdf//734vGhx9+eHTu3LlFewEAAAAAAAAAAAAAAAAAoNzE2jupE044oWh8//33t2jfCy+8EPPnzy+M99hjjxg0aNBm1w8ePDh69uxZGNfW1saUKVNadFfzN40cObJF+wAAAAAAAAAAAAAAAAAAYEcg1t5JnXrqqdGpU6fC+MUXX4x//OMfW9zT1NQUY8eOLZo7++yzo7Jy8/9NKisr46yzziqaGzt27Fa/rv3888/HSy+9VBjvvvvuMWrUqC3uAQAAAAAAAAAAAAAAAACAHYlYeyfVq1evOP/884vmzjnnnHjvvfc2u+fGG2+MF198sTDu0qVLXHrppVu96/LLL4/OnTsXxv/85z/jpptu2uz6xYsXxznnnFM0d8EFFxR9oRsAAAAAAAAAAAAAAAAAAHZ0bcr9gF3V1KlTY/Xq1RvN/+c//ykaNzQ0xOTJkzd5Ru/evaOmpmazd1x22WXx+9//Pt5///2IiJg/f34MHjw47rjjjhgxYkRUVFRERMSiRYviuuuui7vvvrto/5VXXhndu3ff6t/Ss2fPuOKKK+KKK64ozI0ePToWLlwYv/zlL6N3794REdHY2BhPP/10XHDBBbFw4cKiv+PnP//5Vu8BAAAAAAAAAAAAAAAAAIAdiVi7TE4//fRYsGDBVtd98MEHMWzYsE3+duaZZ8aDDz642b3du3ePxx57LI455phoaGiIiIgFCxbEyJEjo2vXrtG3b99YsWJFLFy4MDZs2FC0d+TIkXHJJZe0+O+5/PLLY9q0afHss88W5u6666645557orq6Orp06RLz58+PFStWFO3r0KFDPP7449G1a9cW3wUAAAAAAAAAAAAAAAAAADuCynI/gG1ryJAhMXHixI2+kL1ixYqYOXNmzJ8/f6NQ+3vf+1489thjhS9vt0RlZWU88cQTceqppxbNb9iwIWpra2PmzJkbhdo9evSIv/71r3HooYeW9kcBAAAAAAAAAAAAAAAAAMAOQKy9CzjiiCNi9uzZ8dOf/jQ6duy42XUHH3xw/OUvf4mHH3442rVrV/I97du3jz/96U/x5z//OQYOHLjZdZ06dYrzzjsvZs+eHUOHDi35HgAAAAAAAAAAAAAAAAAA2BG0KfcDdlV1dXXb9b499tgj7rzzzrjtttti2rRpMWfOnFixYkVUVVXFnnvuGYMGDYr99tuvVe466aST4qSTTop58+bF9OnTY/HixbF27dro2rVrfPnLX45DDz002rdv3yp3AQAAAAAAAAAAAAAAAABAuYi1dzEdOnSII488Mo488shtftd+++3XagE4AAAAAAAAAAAAAAAAAADsaCrL/QAAAAAAAAAAAAAAAAAAAIDPI7E2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAA/B97dx6u13zvjf+9dnbmRCQk5gQxxhxDjRUpotTwVFM1tj36UHoOHZTHo6bS0odDaR3joU6VnmOooQQ9gqrTqqlIxJBEImgiMslONpnW7w+/3LVFSO694947+/W6rvvy/a691me9F/2nf7yvLwAAAAAAAAAAAABUQVkbAAAAAAAAAAAAAAAAAACgCsraAAAAAAAAAAAAAAAAAAAAVVDWBgAAAAAAAAAAAAAAAAAAqIKyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKqgrA0AAAAAAAAAAAAAAAAAAFAFZW0AAAAAAAAAAAAAAAAAAIAqKGsDAAAAAAAAAAAAAAAAAABUQVkbAAAAAAAAAAAAAAAAAACgCsraAAAAAAAAAAAAAAAAAAAAVVDWBgAAAAAAAAAAAAAAAAAAqIKyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKqgrA0AAAAAAAAAAAAAAAAAAFAFZW0AAAAAAAAAAAAAAAAAAIAqKGsDAAAAAAAAAAAAAAAAAABUQVkbAAAAAAAAAAAAAAAAAACgCsraAAAAAAAAAAAAAAAAAAAAVVDWBgAAAAAAAAAAAAAAAAAAqIKyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKqgrA0AAAAAAAAAAAAAAAAAAFAFZW0AAAAAAAAAAAAAAAAAAIAqKGsDAAAAAAAAAAAAAAAAAABUQVkbAAAAAAAAAAAAAAAAAACgCsraAAAAAAAAAAAAAAAAAAAAVVDWBgAAAAAAAAAAAAAAAAAAqIKyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKqgrA0AAAAAAAAAAAAAAAAAAFAFZW0AAAAAAAAAAAAAAAAAAIAqKGsDAAAAAAAAAAAAAAAAAABUQVkbAAAAAAAAAAAAAAAAAACgCsraAAAAAAAAAAAAAAAAAAAAVVDWBgAAAAAAAAAAAAAAAAAAqIKyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKqgrA0AAAAAAAAAAAAAAAAAAFAFZW0AAAAAAAAAAAAAAAAAAIAqKGsDAAAAAAAAAAAAAAAAAABUQVkbAAAAAAAAAAAAAAAAAACgCsraAAAAAAAAAAAAAAAAAAAAVVDWBgAAAAAAAAAAAAAAAAAAqIKyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKqgrA0AAAAAAAAAAAAAAAAAAFAFZW0AAAAAAAAAAAAAAAAAAIAqKGsDAAAAAAAAAAAAAAAAAABUQVkbAAAAAAAAAAAAAAAAAACgCsraAAAAAAAAAAAAAAAAAAAAVVDWBgAAAAAAAAAAAAAAAAAAqIKyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKqgrA0AAAAAAAAAAAAAAAAAAFCF+loHAACAz9r6/+feWkegGSZceECtIwAAAAAAAAAAAAAAACRxsjYAAAAAAAAAAAAAAAAAAEBVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqUF/rACvKG2+8kSuuuCJ/+tOf8s4776R3797Zfvvt80//9E/Zbrvtah0PAAAAAAAAAAAAAAAAAABo49pEWfuJJ57IFVdcUdmfddZZ2WijjZZ6/2233Zavf/3ree+995IkZVmmKIo88cQTueqqq3Laaafl/PPPX+G5AQAAAAAAAAAAAAAAAACAlVebKGtfc801uemmm1IURTbccMNPLGo//fTTOeqoozJv3rwkSVEUKYqi8veFCxfmggsuSKdOnXLWWWet8OwAAAAAAAAAAAAAAAAAAMDKqa7WAZbFAw88UFkfccQRn3jvd7/73cybN69S0i7Lsslv8bXzzz8/o0ePXtHRAQAAAAAAAAAAAAAAAACAlVSrL2u/8cYbeeuttyr7/ffff6n3/vWvf83jjz9eOUl7gw02yH//93+nsbExkyZNyr/8y79UCtsLFy7MRRddtMLzAwAAAAAAAAAAAAAAAAAAK6dWX9Z+6aWXKuu6urpsu+22S7335ptvTpKUZZm6urrcfffdGTp0aDp37px11lknl112Wb761a9WTtn+3e9+l/nz56/oTwAAAAAAAAAAAAAAAAAAAFZCrb6sPWHChCRJURTp379/OnfuvNR7H3jggcq9++67bwYNGrTEPaeffnpl3dDQkBdeeKFlAwMAAAAAAAAAAAAAAAAAAO1Cqy9rv/vuu5V17969l3rflClT8vLLL6coiiTJl7/85Y+9b5tttsmqq65a2Y8ePbplggIAAAAAAAAAAAAAAAAAAO1Kqy9rNzY2VtafdKr2n//85yRJWZZJki984QtLvXf99devrKdNm9bMhAAAAAAAAAAAAAAAAAAAQHvU6svaXbt2raw/fMr2Rz366KOV9dprr92kkP1RXbp0qaznzp3bvIAAAAAAAAAAAAAAAAAAAEC71OrL2r17907ywYnZEyZMqJyc/VEPPvhgkqQoinz+85//xJmzZ8+urD/ptG4AAAAAAAAAAAAAAAAAAIClafVl7UGDBlXWc+fOzeOPP77EPaNGjcqYMWNSFEWSZMiQIZ848+23366sF5fBAQAAAAAAAAAAAAAAAAAAlkerL2tvs8026d69e6WIfe655y5xz3nnnZcklVO3991336XOmzx5cqZOnVrZb7DBBi0ZFwAAAAAAAAAAAAAAAAAAaCdafVm7S5cu+V//639VitgjR47MPvvsk1tvvTV33nlnhg8fnltvvTVFUaQoiuy+++4ZMGDAUuf95S9/abLfbLPNVmh+AAAAAAAAAAAAAAAAAABg5VRf6wDL4uyzz86tt96aefPmpSzLjBw5MiNHjmxyT1mWKYoiP/rRjz5x1p133llZr7feellrrbVWRGQAAAAAAAAAAAAAAAAAAGAl1+pP1k6SgQMH5pprrkmSFEWR5INy9uLTthdfO+6447LPPvssdU5jY2Puuuuuyince+655wpODgAAAAAAAAAAAAAAAAAArKzaRFk7SY4++ujcf//92WyzzSol7eSD0nbPnj3zk5/8JFdeeeUnzrjhhhsya9asyvNf+tKXVmhmAAAAAAAAAAAAAAAAAABg5VVf6wDLY5999sno0aMzZsyYvPLKK2lsbMzaa6+dz33uc+ncufOnPr9gwYKcfPLJlf0Xv/jFFRkXAAAAAAAAAAAAAAAAAABYibWpsvZim2++eTbffPPlfu6kk05aAWkAAAAAAAAAAAAAAAAAAID2qK7WAQAAAAAAAAAAAAAAAAAAANoiZW0AAAAAAAAAAAAAAAAAAIAqKGsDAAAAAAAAAAAAAAAAAABUob7WAar17rvv5oEHHshjjz2WMWPGZPr06Zk1a1bKssxNN92UXXbZpdYRAQAAAAAAAAAAAAAAAACAlVibK2vPmDEjP/7xj3P99denoaGhyd/KskxRFGlsbPzYZ7/2ta/l1ltvTZL0798/r7322grPCwAAAAAAAAAAAAAAAAAArJzqah1gefzP//xPtt1221x++eWZPXt2yrJcrud/+MMfpizLlGWZ119/PQ899NAKSgoAAAAAAAAAAAAAAAAAAKzs2kxZ+6mnnsq+++6bN954o8n1oiiy+uqrL1Nxe/vtt8/gwYMr+9tuu63FcwIAAAAAAAAAAAAAAAAAAO1DmyhrNzQ05KCDDsrcuXOTJGVZZuedd85dd92Vd999N1OmTEnyQXH70xx66KGVGQ8++OCKCw0AAAAAAAAAAAAAAAAAAKzU2kRZ+6KLLsrkyZMrZex/+Zd/yZ/+9KcceOCB6dat23LN2nvvvSvrCRMmZPLkyS2aFQAAAAAAAAAAAAAAAAAAaB/aRFn76quvrhS1hw4dmssuuyx1ddVF33rrrdOhQ4fK/sUXX2yRjAAAAAAAAAAAAAAAAAAAQPvS6svazzzzTN5+++2UZZkk+fGPf9yseZ07d866665b2b/22mvNmgcAAAAAAAAAAAAAAAAAALRPrb6s/eGTr3v37p1ddtml2TNXXXXVynrWrFnNngcAAAAAAAAAAAAAAAAAALQ/rb6s/fbbbydJiqLIgAEDWmRmly5dKuv333+/RWYCAAAAAAAAAAAAAAAAAADtS6svay9cuLCy7tChQ4vMnDFjRmX94VO2AQAAAAAAAAAAAAAAAAAAllWrL2v369cvSVKWZaZMmdLsefPmzcvEiRMr+9VXX73ZMwEAAAAAAAAAAAAAAAAAgPan1Ze111lnncr6jTfeyNtvv92seY8//njef//9yn6LLbZo1jwAAAAAAAAAAAAAAAAAAKB9avVl7d122y2dO3dOURRJkt/85jfNmvfLX/6ysu7Xr18GDRrUrHkAAAAAAAAAAAAAAAAAAED71OrL2l27ds1ee+2VsixTlmV+9rOfZdq0aVXNuueee3LnnXemKIoURZFDDjmkZcMCAAAAAAAAAAAAAAAAAADtRqsvayfJGWeckSQpiiJTp07NQQcdlJkzZy7XjBEjRuSoo45KkpRlmfr6+px22mktHRUAAAAAAAAAAAAAAAAAAGgn2kRZe7fddstXvvKVlGWZJPnLX/6SLbfcMv/+7/+ehoaGpT63cOHC/M///E8OP/zwHHTQQZk9e3bKskxRFDnppJOy/vrrf0ZfAAAAAAAAAAAAAAAAAAAArGzqax1gWf3qV7/K+PHj88wzz6Qoirz11ls57rjjcuKJJ2aTTTZJkkoR++STT05Zlpk4cWLmzp3b5G9lWWbIkCH52c9+VsvPAQAAAAAAAAAAAAAAAAAA2rg2cbJ2knTr1i0jRozIkCFDmhSv58+fn9GjR1fuK8syL774Yl588cXMmTOnchr34vv333///O53v0tdXZv5dAAAAAAAAAAAAAAAAAAAoBVqU43lvn375qGHHsoFF1yQ3r17V64XRdHk9+FryQcF7l69euWCCy7IPffck1VWWaUm+QEAAAAAAAAAAAAAAAAAgJVHmyprJx+UsE877bRMmjQpV155ZQ488MD07t07ZVku8evSpUv23nvvXHzxxZkwYUJOO+20SoEbAAAAAAAAAAAAAAAAAACgOeprHaBaXbt2zfHHH5/jjz8+STJlypRMmzYtM2fOTLdu3bL66qtnzTXXTH19m/1EAAAAAAAAAAAAAAAAAACgFVtpmsxrrLFG1lhjjVrHAAAAAAAAAAAAAAAAAAAA2om6WgcAAAAAAAAAAAAAAAAAAABoi5S1AQAAAAAAAAAAAAAAAAAAqqCsDQAAAAAAAAAAAAAAAAAAUIU2UdZ+/vnns+GGG1Z+jz76aFVzHnnkkcqMgQMH5pVXXmnhpAAAAAAAAAAAAAAAAAAAQHvRJsraV155ZSZMmJAJEyakW7du2XPPPauaM2TIkHTu3Lky6+qrr27hpAAAAAAAAAAAAAAAAAAAQHvRJiUnYNQAANEMSURBVMrad911V5KkKIocddRRzZp1zDHHJEnKsszvfve7ZmcDAAAAAAAAAAAAAAAAAADap1Zf1h4zZkwmT55c2R988MHNmvfh5ydOnJjXXnutWfMAAAAAAAAAAAAAAAAAAID2qdWXtV988cXKukePHtl8882bNW/zzTdPjx49KvtRo0Y1ax4AAAAAAAAAAAAAAAAAANA+tfqy9ptvvpkkKYoi6623XrPnFUWR/v37V/avv/56s2cCAAAAAAAAAAAAAAAAAADtT6svazc0NFTWq6yySovM7NmzZ2U9e/bsFpkJAAAAAAAAAAAAAAAAAAC0L62+rP3hYvWMGTNaZObMmTMr606dOrXITAAAAAAAAAAAAAAAAAAAoH1p9WXt1VdfPUlSlmUmTZqU+fPnN2vevHnzMmnSpMq+b9++zZoHAAAAAAAAAAAAAAAAAAC0T62+rD1w4MDKurGxMY8++miz5j366KOZO3duZT9gwIBmzQMAAAAAAAAAAAAAAAAAANqnVl/W3mGHHdKrV68URZEkueCCC5o178ILL6ysu3fvnl122aVZ8wAAAAAAAAAAAAAAAAAAgPap1Ze16+rqsv/++6csy5RlmUceeSSXXnppVbMuueSSPPzwwymKIkVRZNiwYenYsWMLJwYAAAAAAAAAAAAAAAAAANqDVl/WTpIzzjgjdXV1KYoiZVnmhz/8Yc4666wsXLhwmZ5fuHBhzjzzzJx66qmVGUVR5Mwzz1zByQEAAAAAAAAAAAAAAAAAgJVVmyhrDxo0KMcdd1ylZL1o0aL85Cc/yWabbZZLL700L7300sc+99JLL+WSSy7JZpttlp/+9KdZtGhRkqQoihx77LHZeuutP8vPAAAAAAAAAAAAAAAAAAAAViL1tQ6wrC6//PKMHj06jz32WOV07HHjxuWUU07JKaecku7du2f11VdPjx490tDQkHfeeSdz5sxJkpRlmSSV54YMGZIrrriilp8DAAAAAAAAAAAAAAAAAAC0cW3iZO0kqa+vzz333JNDDjmkcsL24vJ1WZZpaGjIhAkTMmrUqEyYMCENDQ2Vv3343q985Su56667Ul/fZnrqAAAAAAAAAAAAAAAAAABAK9RmytpJssoqq+SOO+7IlVdemfXWW6/JidlL+yUfnKw9YMCAXHfddfmv//qv9OzZs5afAQAAAAAAAAAAAAAAAAAArATa5PHSxx9/fL71rW/ljjvuyIMPPpjHHnss48ePz4IFCyr31NfXZ6ONNsoee+yR/fbbLwcffHDq6tpUNx0AAAAAAAAAAAAAAAAAAGjF2mRZO0k6dOiQ4cOHZ/jw4ZVrs2fPzuzZs9OzZ0+nZwMAAAAAAAAAAAAAAAAAACtUmy1rfxwlbQAAAAAAAAAAAAAAAAAA4LNSV+sAAAAAAAAAAAAAAAAAAAAAbZGyNgAAAAAAAAAAAAAAAAAAQBWUtQEAAAAAAAAAAAAAAAAAAKpQX+sAzTV//vzMmjUrjY2NKctyuZ/v37//CkgFAAAAAAAAAAAAAAAAAACs7NpcWXvGjBm56aabMmLEiDzzzDOZOnVq1bOKosiCBQtaMB0AAAAAAAAAAAAAAAAAANBetKmy9s9//vOceeaZmTt3bpJUdZI2AAAAAAAAAAAAAAAAAABAS2gzZe1vf/vbufbaaysF7aIoUhSFwjYAAAAAAAAAAAAAAAAAAFATbaKsfeONN+aaa65JkkpBuyzL9O7dO1tttVX69euX7t271zglAAAAAAAAAAAAAAAAAADQnrSJsvZZZ52V5B9F7W222SYXXnhh9tlnn9TV1dU4HQAAAAAAAAAAAAAAAAAA0B61+rL2s88+m0mTJqUoiiTJrrvumj/84Q/p2rVrjZMBAAAAAAAAAAAAAAAAAADtWas/lvpvf/tbkqQsyyTJL3/5S0VtAAAAAAAAAAAAAAAAAACg5lp9WXvq1KmV9dprr51tt922dmEAAAAAAAAAAAAAAAAAAAD+f62+rF0UReWf66yzTo3TAAAAAAAAAAAAAAAAAAAAfKDVl7X79+9fWTc0NNQwCQAAAAAAAAAAAAAAAAAAwD+0+rL2rrvumiQpyzITJkzIvHnzapwIAAAAAAAAAAAAAAAAAACgDZS111tvvey1115JksbGxowYMaLGiQAAAAAAAAAAAAAAAAAAANpAWTtJLrzwwnTo0CFJcsYZZ+S9996rcSIAAAAAAAAAAAAAAAAAAKC9q691gGWx44475l//9V/z3e9+N2PGjMmhhx6a3/72t+nZs2eto7VJ77//fp599tmMGTMmM2bMSGNjY1ZZZZX069cvgwcPzkYbbZSiKJr9ngULFuSJJ57IqFGjMm3atHTo0CFrrbVWtt9++2yxxRYt8CUAAAAAAAAAAAAAAAAAAFA7baKsnSQnnXRSOnfunJNPPjn3339/tt5665x++ukZPnx4evfuXet4bcLTTz+dSy+9NLfddlvef//9pd63zjrr5Nhjj83JJ5+cPn36LPd7GhoacuGFF+bKK6/M9OnTP/aeTTfdNKeddlq+8Y1vtEgxHAAAAAAAAAAAAAAAAAAAPmttoqw9dOjQyrpv37558803M3HixJxwwgk58cQTs/7666dfv37p0qXLcs0tiiIPPfRQS8dtdRYtWpT/+3//by666KIsWrToU+9/88038+Mf/zhXX311fvWrX2W//fZb5ne98MILOfjgg/Paa6994n0vv/xy/umf/in/+Z//mf/8z/9Mr169lvkdAAAAAAAAAAAAAAAAAADQGrSJsvYjjzzS5PTlxeuyLFOWZcaPH/+p5eCPKsuy3ZzofPzxx+e6665b4nq3bt0ycODAdO3aNdOmTcv48eNTlmXl71OmTMnBBx+cO++8M1/84hc/9T0vv/xyhg4dmnfeeafJ9R49emTDDTdMY2NjJkyYkPnz51f+9sADD+SLX/xiRo4cudxlewAAAAAAAAAAAAAAAAAAqKW6WgdojqIoKj8+3m233bZEUXvQoEG59957M2vWrDz//PN54oknMnbs2EyZMiXnnntuOnXqVLl33rx5+frXv54ZM2Z84nsWLFiQ4cOHNylq9+nTJzfeeGOmT5+e5557Lq+88komT56cM844I3V1//if3p///OeceuqpLfTFAAAAAAAAAAAAAAAAAADw2WgzZe3Fp2i31K+9OPfcc5vsd9hhh/z1r3/N/vvvn/r6pger9+3bN2eddVZGjBjR5G9Tp07NVVdd9Ynvuf766/PCCy9U9r17985jjz2WY445Jh07dqxc79OnT84///z8+te/bvL8lVdemVdffXW5vw8AAAAAAAAAAAAAAAAAAGqlTZS1Fy1atEJ+CxcurPWnrVDjx4/PqFGjmlz7t3/7t3Tv3v0Tnxs6dGiOPfbYJtfuueeepd4/b968nH/++U2uXXzxxRk0aNBSnzniiCNy1FFHVfYLFizIOeec84m5AAAAAAAAAAAAAAAAAACgNWkTZW2q8/LLLzfZr7vuutlxxx2X6dlDDz20yX7s2LFLvfeBBx7IpEmTKvv1118/3/zmNz/1Heecc06Koqjsb7311syaNWuZ8gEAAAAAAAAAAAAAAAAAQK0pa6/Epk+f3mS/3nrrLfOz/fv3b7KfOXPmUu+96667muy/+c1vNilhL83AgQOz5557Vvbz58/Pfffdt8wZAQAAAAAAAAAAAAAAAACglpS1V2K9evVqsm9sbFzmZz967+qrr77Ue++9994m+3333XeZ37PPPvs02f/+979f5mcBAAAAAAAAAAAAAAAAAKCWlLVXYttuu22T/ZgxYzJnzpxlevavf/1rk/1OO+30sfdNmTIlkydPruw7d+6cwYMHL3PG3Xbbrcn+b3/72zI/CwAAAAAAAAAAAAAAAAAAtaSsvRJbd911s+uuu1b277//fi6//PJPfe7999/Pz3/+8ybXjj322I+9d8yYMU32G220UTp16rTMGQcNGtRkP3bs2CxYsGCZnwcAAAAAAAAAAAAAAAAAgFpps2XtsWPH5qKLLspBBx2UjTfeOKuttlrq6+tTX1+fkSNHfuwzf//73/P666/n9ddfz9SpUz/jxLXxs5/9LHV1//jPfNZZZ+XGG29c6v0zZ87MV77ylSYl7AMPPDAHHnjgx97/8ssvN9mvt956y5Wvb9++6dKlS2U/b968vPbaa8s1AwAAAAAAAAAAAAAAAAAAaqG+1gGW1/jx4/ODH/wg99xzT8qyTJLKP5OkKIqlPnvOOefkuuuuS/JBSfjNN99Mhw4dVmzgGtt9993zy1/+Mt/5zndSlmUWLFiQb3zjG7niiivy5S9/OZtuumm6du2ad955J0888URuvvnmTJ8+vfL8Pvvsk1tuuWWp899+++0m+3XXXXe5M6699toZP358k5kbb7zxcs/5aK7lLeSPHTu2We8EAAAAAAAAAAAAAAAAAKB9aVNl7dtvvz3HHntsZs+enbIsmxSzi6JoUtr+OD/4wQ9y3XXXpSzLTJ06Nb///e9z8MEHr+jYNXfCCSdk0003zUknnZTRo0cnSZ588sk8+eSTS31mww03zKmnnpr//b//d5OTuT+qoaGhyb579+7Lne+jz3x0ZjX+7d/+Leeee26z5wAAAAAAAAAAAAAAAAAAwNIsvYXbytx333352te+lnfffbdyrSzLrLHGGtlxxx0/taidJJtsskl22223yv6OO+5YIVlbo6FDh+bJJ5/MKaec8qmniffv3z+nnHJKjjjiiE8saidLFqu7dOmy3Nm6du36iTMBAAAAAAAAAAAAAAAAAKA1ahNl7alTp+bwww/PwoULKydoDx8+PM8991zeeuutPPHEE0nS5KTtpTn00EOTfFD0/u///u8Vmrs1ueqqqzJw4MBcfPHFWbhw4Sfe+/rrr+fEE0/M+uuvn+uvv/4T733vvfea7Dt16rTc2Tp37txk39jYuNwzAAAAAAAAAAAAAAAAAADgs1Zf6wDL4rzzzsvs2bMr+//3//5fTjnllKpm7bXXXpX15MmT8/rrr6d///7NzthazZ8/P4cffnhuv/32yrU+ffrkn//5n/OlL30pG2+8cbp375533nknTz31VG644YbceeedKcsy06dPz7HHHpsxY8bkoosu+tj5Hz1Je968ecud8f333//EmdU48cQTM3z48OV6ZuzYsTnkkEOa/W4AAAAAAAAAAAAAAAAAANqHVl/WXrRoUW666abKqdlf+cpXqi5qJ8mgQYPSqVOnSql4zJgxK3VZ+4QTTmhS1N5pp51y1113Zc0112xy31prrZUDDzwwBx54YO6+++4cdthhlVOzL7744gwaNCjf/OY3l5jfo0ePJvuPnrS9LD56kvZHZ1ajX79+6devX7PnAAAAAAAAAAAAAAAAAADA0tTVOsCn+ctf/pKZM2emLMskyY9+9KNmzauvr88666xT2b/++uvNmteaPfLII/n3f//3yr5fv375/e9/v0RR+6MOOuigXHHFFU2u/fCHP1yiVJ0sWayeM2fOcuf86DMtUdYGAAAAAAAAAAAAAAAAAIAVrdWXtV999dXKul+/ftlqq62aPXPVVVetrGfNmtXsea3V5Zdf3mT/3e9+N3379l2mZ7/xjW9kk002qeynTZuWO+64Y4n7Pnp69RtvvLHcOd96661PnAkAAAAAAAAAAAAAAAAAAK1Rqy9rT506NUlSFEXWXXfdFplZX19fWS9YsKBFZrY2ZVlm5MiRTa4deOCBy/x8XV1dDjjggCbX/vjHPy5x36abbtpkv7wnlb/99tt57733KvtOnTplww03XK4ZAAAAAAAAAAAAAAAAAABQC62+rF1X94+IixYtapGZ06dPr6x79+7dIjNbmxkzZixxavgGG2ywXDM+ev+bb765xD2bbbZZk/24ceMyb968ZX7HmDFjmuwHDhzYpEwPAAAAAAAAAAAAAAAAAACtVasva/ft2zfJBydFT548udnz5s6dm4kTJ6YoiibzVzbvv//+EteWtwTdsWPHJvuFCxcucc+aa66ZNddcs8l7n3766WV+x+OPP95kv+222y5XRgAAAAAAAAAAAAAAAAAAqJVWX9Zef/31K+vJkydn4sSJzZr38MMPZ8GCBSnLMsnKWw5ebbXVlrj21ltvLdeMj56kvbRi+wEHHNBk/4c//GGZ3/HRew888MBlfhYAAAAAAAAAAAAAAAAAAGqp1Ze1d9555/To0aNyEvavfvWrZs279NJLK+v+/ftnww03bNa81qpTp05Za621mlwbOXLkcs146KGHmuwHDhz4sfcddNBBTfY33HBDpQz/ScaNG5dHH320su/YsWP233//5coIAAAAAAAAAAAAAAAAAAC10urL2h07dsx+++2XsixTlmUuueSSTJgwoapZ1113XUaOHJmiKFIURb761a+2bNhW5gtf+EKT/c9//vMsWLBgmZ599NFH8+c///kT5y02bNiwrLvuupX9hAkTcsMNN3zqO84555wmpe5DDz00vXr1WqZ8AAAAAAAAAAAAAAAAAABQa62+rJ0kZ599durq6lIURWbPnp1hw4Ytd2H76quvzj//8z+nKIqUZZmuXbvmlFNOWTGBW4mjjjqqyX7UqFE58cQTs2jRok98buzYsTniiCOaXNt4442zyy67fOz9nTt3zhlnnNHk2imnnJIXX3xxqe+4+eabc9NNN1X2HTp0yLnnnvuJuQAAAAAAAAAAAAAAAAAAoDVpE2XtLbbYIieccELKskxRFHn11Vez1VZb5cwzz8wrr7yyxP1FUSRJJk+enJtvvjm77rprTjzxxMybN68y45xzzknfvn0/60/5TA0bNix77bVXk2vXXntt9txzzzz00ENLnLI9bdq0/Ou//mt22GGHvPXWW03+9tOf/jQdOnRY6ruOPfbYbLHFFpX9jBkzsscee+Q//uM/mrxn+vTpOfPMM3P00Uc3ef7444/PJptsstzfCAAAAAAAAAAAAAAAAAAAtVKUZVnWOsSyWLhwYQ444IA8+OCDldOxF5eyu3fvnoaGhiQfFLX79OmTxsbGNDY2Vp5ffH9ZljnssMNyyy231OQ7PmuTJ0/Orrvumtdee22Jv/Xo0SMbbLBBunbtmmnTpmX8+PH5uP85/OAHP8jFF1/8qe8aM2ZMdt9990yfPn2J9wwcODCNjY157bXXMn/+/CZ/32mnnfLII4+ka9euy/l1LWv06NHZcsstK/tRo0Y1KaADtJT1/8+9tY4A0KZNuPCAWkcA2orRo5MP/f+8jzVqVOL/+wEAAAAAAAAAAABAm1XrfmibOFk7STp06JDf/e53Ofroo5sUtcuyTENDQ5P9tGnTMnfu3JRl2aR8XJZljj/++Pz617+uyTfUwpprrplHH300Q4YMWeJvDQ0NeeGFF/LXv/4148aNW6Ko3bFjx1x44YW56KKLluldm2++eUaOHJkBAwYs8Z7nnnsur7zyyhJF7b333jsPPPBAzYvaAAAAAAAAAAAAAAAAAACwvNpMWTtJunbtmhtvvDG33HJLNt1000q5eHFRuyiKJX7JByXtjTbaKLfcckuuvPLK1NfX1+wbamG99dbLQw89lP/6r//KkCFDUlf3yf/Ze/XqlRNOOCEvvPBCTjvttMq/x2WxzTbb5IUXXsjpp5+e3r17L/W+jTfeONdee20efPDBrLrqqss8HwAAAAAAAAAAAAAAAAAAWos22Vo+7LDDcthhh+WBBx7Ifffdl8ceeyxjxozJ+++/X7mnvr4+AwYMyF577ZX99tsvhxxyyKeWlFdmdXV1GT58eIYPH57Zs2fnqaeeyvjx4zNz5sy89957WWWVVbLaaqtl6623zqBBg5r176pnz5756U9/mnPPPTdPPPFERo0alWnTpqVDhw5Za621Mnjw4Gy11VYt+HUAAAAAAAAAAAAAAAAAAPDZa5Nl7cWGDRuWYcOGVfZz587NzJkz061bN6c1f4KePXtmr732yl577bVC39OxY8fsvvvu2X333VfoewAAAAAAAAAAAAAAAAAAoBZafVn71VdfzYgRIyr7vffeO4MGDfrYe7t165Zu3bp9VtEAAAAAAAAAAAAAAAAAAIB2rNWXte+///5873vfS5IURZFx48bVOBEAAAAAAAAAAAAAAAAAAEBSV+sAn6ahoSFlWaYsy6y99toZMGBArSMBAAAAAAAAAAAAAAAAAAC0/rJ23759k3xwqvbaa69d4zQAAAAAAAAAAAAAAAAAAAAfaPVl7Q8XtGfNmlXDJAAAAAAAAAAAAAAAAAAAAP/Q6svaO++8czp27JiyLDNhwoTMmTOn1pEAAAAAAAAAAAAAAAAAAABaf1m7T58+GTZsWJJk3rx5ue2222qcCAAAAAAAAAAAAAAAAAAAoA2UtZPk9NNPT1EUSZIzzjgjU6dOrXEiAAAAAAAAAAAAAAAAAACgvWsTZe1ddtklF1xwQcqyzN///vcMHTo0Y8aMqXUsAAAAAAAAAAAAAAAAAACgHWsTZe0kOfXUU3PVVVelS5cuGT16dLbbbrt84xvfyP3335/p06fXOh4AAAAAAAAAAAAAAAAAANDO1Nc6wLLYcMMNK+v6+g8iz5s3L7/+9a/z61//OknSo0ePrLLKKunYseMyzy2KIuPGjWvZsAAAAAAAAAAAAAAAAAAAQLvQJsraEyZMSFEUKcsyRVGkKIokSVmWlXtmz56d2bNnL9fcxXMAAAAAAAAAAAAAAAAAAACWV5soay/20XJ1c8rWHy56AwAAAAAAAAAAAAAAAAAALK82Udbu37+/U7ABAAAAAAAAAAAAAAAAAIBWpU2UtSdMmFDrCAAAAAAAAAAAAAAAAAAAAE3U1ToAAAAAAAAAAAAAAAAAAABAW9TqT9ZeuHBh5syZU9l37do1HTt2rGEiAAAAAAAAAAAAAAAAAACANnCy9o033pjevXtXfo899litIwEAAAAAAAAAAAAAAAAAALT+svaUKVNSlmXKskyvXr0ydOjQWkcCAAAAAAAAAAAAAAAAAABo/WXtHj16JEmKosiAAQNqnAYAAAAAAAAAAAAAAAAAAOADrb6svdZaa9U6AgAAAAAAAAAAAAAAAAAAwBJafVl78803T5KUZZlJkybVOA0AAAAAAAAAAAAAAAAAAMAHWn1Ze4sttsgWW2yRJJkxY0aeeOKJGicCAAAAAAAAAAAAAAAAAABoA2XtJDnuuOMq67PPPruGSQAAAAAAAAAAAAAAAAAAAD7QJsraJ554YnbbbbeUZZk//OEPOeWUU2odCQAAAAAAAAAAAAAAAAAAaOfaRFm7Q4cOueeee7L77runLMtceuml+fznP59HHnmk1tEAAAAAAAAAAAAAAAAAAIB2qr7WAZbFj3/84yTJnnvumVdffTVTpkzJ448/ni984QtZY401ssMOO2SDDTbIKqusko4dOy7X7LPOOmtFRAYAAAAAAAAAAAAAAAAAAFZybaKsfc4556Qoisq+KIqUZZkkmTx5cu69996qZytrAwAAAAAAAAAAAAAAAAAA1WgTZe2P8+HydjXKsmz2DAAAAAAAAAAAAAAAAAAAoP1qM2XtxSdpAwAAAAAAAAAAAAAAAAAAtAZtoqz98MMP1zoCAAAAAAAAAAAAAAAAAABAE22irL3nnnvWOgIAAAAAAAAAAAAAAAAAAEATdbUOAAAAAAAAAAAAAAAAAAAA0BYpawMAAAAAAAAAAAAAAAAAAFRBWRsAAAAAAAAAAAAAAAAAAKAKytoAAAAAAAAAAAAAAAAAAABVUNYGAAAAAAAAAAAAAAAAAACoQn2tAyyLP/7xjyts9uc///kVNhsAAAAAAAAAAAAAAAAAAFh5tYmy9pAhQ1IURYvPLYoiCxYsaPG5AAAAAAAAAAAAAAAAAADAyq9NlLUXK8uy1hEAAAAAAAAAAAAAAAAAAACStKGydrVF7Y+eyK3wDQAAAAAAAAAAAAAAAAAAtIQ2UdY+++yzl/uZuXPnZurUqXnyySczevToJB8UtzfaaKMceeSRLR0RAAAAAAAAAAAAAAAAAABoZ1basvaHjRo1KmeccUbuueeejBs3LmPHjs0NN9yQ+vo28fkAAAAAAAAAAAAAAAAAAEArVFfrAJ+FLbfcMnfddVfOOOOMlGWZm2++Od/85jdrHQsAAAAAAAAAAAAAAAAAAGjD2kVZe7Hzzjsvw4YNqxS2b7nlllpHAgAAAAAAAAAAAAAAAAAA2qh2VdZOkrPPPjtJUpZlZQ0AAAAAAAAAAAAAAAAAALC82l1Ze+edd06fPn2SJOPGjcuzzz5b40QAAAAAAAAAAAAAAAAAAEBb1O7K2knSv3//yvqZZ56pYRIAAAAAAAAAAAAAAAAAAKCtapdl7bq6f3z222+/XcMkAAAAAAAAAAAAAAAAAABAW9XuytqLFi3K+PHjK/suXbrUMA0AAAAAAAAAAAAAAAAAANBWtbuy9u9///vMnDmzsl9zzTVrFwYAAAAAAAAAAAAAAAAAAGiz2lVZe9y4cfnOd76Toigq13bfffcaJgIAAAAAAAAAAAAAAAAAANqqlb6svXDhwjz33HM544wzst122+Wtt95KWZYpiiK77LJL1ltvvVpHBAAAAAAAAAAAAAAAAAAA2qD6WgdYFhtuuGFVzzU2NmbGjBmZP39+klRK2knSoUOHXHzxxS2WEQAAAAAAAAAAAAAAAAAAaF/aRFl7woQJKYoiZVlWPaMoisqMDh065Nprr83OO+/cgikBAAAAAAAAAAAAAAAAAID2pE2UtRdbfCr28lhc8F78z5122im/+MUvsuOOO7ZoNgAAAAAAAAAAAAAAAAAAoH1pE2Xt/v37L3dRuyiKdOnSJausskoGDBiQwYMHZ//9989WW221glICAAAAAAAAAAAAAAAAAADtSZsoa0+YMKHWEQAAAAAAAAAAAAAAAAAAAJqoq3UAAAAAAAAAAAAAAAAAAACAtkhZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAV2kRZ+09/+lM6dOhQ+T388MNVzRk5cmRlRn19fZ5++ukWTgoAAAAAAAAAAAAAAAAAALQXbaKsffXVV6csy5RlmR133DF77bVXVXOGDh2a7bbbLmVZZtGiRbn22mtbOCkAAAAAAAAAAAAAAAAAANBetPqy9qJFi3LfffelKIoURZEjjzyyWfOOOeaYJElRFLn77rtbIiIAAAAAAAAAAAAAAAAAANAOtfqy9gsvvJAZM2akLMskyQEHHNCseYufL8syU6ZMycsvv9zsjAAAAAAAAAAAAAAAAAAAQPvT6svaY8aMqaxXXXXVbLjhhs2aN3DgwKy66qqV/ejRo5s1DwAAAAAAAAAAAAAAAAAAaJ9afVl78uTJSZKiKLLOOuu0yMx11123sn7zzTdbZCYAAAAAAAAAAAAAAAAAANC+tPqy9ty5cyvr7t27t8jMD89paGhokZkAAAAAAAAAAAAAAAAAAED70urL2r169aqsp02b1iIzp0+fXll369atRWYCAAAAAAAAAAAAAAAAAADtS6sva/ft2zdJUpZlJk2alMbGxmbNmzt3biZOnJiiKJrMBwAAAAAAAAAAAAAAAAAAWB6tvqy92WabVdbz5s3Lgw8+2Kx5DzzwQObNm5eyLJMkAwcObNY8AAAAAAAAAAAAAAAAAACgfWr1Ze2tt946/fr1S1EUKcsy5513XrPmnX/++ZVTtVddddXstNNOLRETAAAAAAAAAAAAAAAAAABoZ+prHWBZHHLIIbnmmmuSJM8++2y+//3v55JLLlnuOd///vfz7LPPpiiKFEWRQw45pFLcBgAA2ob1/8+9tY5AM0248IBaRwAAAAAAAAAAAAAAgBbR6k/WTpIzzjgjnTp1qpyufdlll+WYY47Ju+++u0zPv/vuuzn66KNz2WWXVWZ07NgxP/rRj1ZwcgAAAAAAAAAAAAAAAAAAYGXVJsra6623Xk4//fSUZVkpW//mN79J//79c9JJJ+X+++/PO++80+SZd955J/fff39OOumkDBgwIDfffHPKsqzMOO2007LBBhvU6IsAAAAAAAAAAAAAAAAAAIC2rr7WAZbV2WefnVGjRuX222+vFLbffffdXHHFFbniiiuSJEVRpFu3bpk7d27Ksqw8u3i9+LmvfvWrOffcc2vyHQAAAAAAAAAAAAAAAAAAwMqhTZysvdgtt9ySk08+uXI6dlEUSVI5MXvRokVpaGjIokWLKteSVO5Lkh/84Ae56aabapIfAAAAAAAAAAAAAAAAAABYebSpsnZ9fX0uvfTSjBgxIp/73OeWKGR/9Jf8o8i9++6758EHH8xFF12UDh061PIzAAAAAAAAAAAAAAAAAACAlUB9rQNUY9iwYRk2bFiefPLJPPjgg3nssccybty4TJ8+PbNnz07Pnj3Tp0+fbLzxxtljjz2y3377Zbvttqt1bAAAAAAAAAAAAAAAAAAAYCXSJsvai+24447Zcccdax0DAAAAAAAAAAAAAAAAAABoh+pqHQAAAAAAAAAAAAAAAAAAAKAtUtYGAAAAAAAAAAAAAAAAAACogrI2AAAAAAAAAAAAAAAAAABAFeprHWBZvf7665V1796907Nnz+WeMXv27MyYMaOy79+/f4tkAwAAAAAAAAAAAAAAAAAA2p82cbL2iBEjssEGG1R+Y8eOrWrOK6+8kvXXX78y55FHHmnZoAAAAAAAAAAAAAAAAAAAQLvRJsra1157bcqyTFmWGTp0aLbbbruq5my//fbZc889K7Ouu+66Fk4KAAAAAAAAAAAAAAAAAAC0F62+rD1//vz84Q9/SFEUKYoihx9+eLPmHXXUUZX1iBEjUpZlcyMCAAAAAAAAAAAAAAAAAADtUKsvaz/33HOZM2dOpVQ9bNiwZs3bb7/9KuuZM2dm1KhRzZoHAAAAAAAAAAAAAAAAAAC0T62+rD1mzJjKum/fvllnnXWaNW+dddZJ3759K/sXX3yxWfMAAAAAAAAAAAAAAAAAAID2qdWXtadOnZokKYoia665ZovMXGuttSrryZMnt8hMAAAAAAAAAAAAAAAAAACgfWn1Ze333nuvsu7SpUuLzOzcuXNlPWfOnBaZCQAAAAAAAAAAAAAAAAAAtC+tvqzdp0+fyvqdd95pkZnTpk2rrHv27NkiMwEAAAAAAAAAAAAAAAAAgPal1Ze1V1999SRJWZZ5/fXXM2vWrGbNmzlzZiZOnJiiKJIkffv2bXZGAAAAAAAAAAAAAAAAAACg/Wn1Ze2tt946SVIURRYuXJh77rmnWfPuvvvuLFy4MGVZJkk233zzZmcEAAAAAAAAAAAAAAAAAADan1Zf1t5kk02y3nrrJfngdO1zzz038+fPr2rWvHnzct5551VO1V5jjTWyzTbbtFhWAAAAAAAAAAAAAAAAAACg/Wj1Ze0k+drXvpayLFMURcaPH5+jjz66qjlHH310xo0bV5l12GGHtXBSAAAAAAAAAAAAAAAAAACgvWgTZe1TTz01PXr0SPLB6dq33nprhgwZkvHjxy/T8+PGjcuQIUNy2223VU7V7tatW04//fQVlhkAAAAAAAAAAAAAAAAAAFi51dc6wLJYbbXVctFFF+WEE05IURQpyzJ//OMfs+mmm+aLX/xi9t9//+ywww7p169fevTokYaGhrz99tt56qmnct9992XEiBFZtGhRyrJMkhRFkYsuuij9+vWr8ZcBAAAAAAAAAAAAAAAAAABtVZsoayfJ8ccfnzFjxuTyyy+vnI69cOHC3Hvvvbn33ns/8dmyLFMURaXo/b3vfS/f/va3P4vYAAAAAAAAAAAAAAAAAADASqqu1gGWx89//vNceumlqa+vrxSwkw/K2Ev7JamUtDt16pRf/OIXufjii2v5GQAAAAAAAAAAAAAAAAAAwEqgTZW1k+Tkk0/OM888k6997Wupq6urFLKTVE7PXlziTj4ocnfo0CFHHXVUnnnmmXznO9+pRWwAAAAAAAAAAAAAAAAAAGAlU1/rANXYYostcvPNN+eSSy7JQw89lMceeyzjxo3L9OnTM3v27PTs2TN9+vTJxhtvnD322CNf+MIX0q9fv1rHBgAAAAAAAAAAAAAAAAAAViJtsqy92JprrpkjjzwyRx55ZK2jAAAAAAAAAAAAAAAAAAAA7UxdrQMAAAAAAAAAAAAAAAAAAAC0RcraAAAAAAAAAAAAAAAAAAAAVaivdYDlNXHixIwZMybTp0/P9OnTM3v27PTs2TN9+vRJnz59svnmm2fAgAG1jgkAAAAAAAAAAAAAAAAAAKzkWn1Ze9GiRbntttty++235/HHH8/f//73T31mrbXWym677ZYvf/nLGT58eOrqHCAOAAAAAAAAAAAAAAAAAAC0rFbbYl6wYEEuvvjibLDBBjn88MNz22235a233kpZlp/6e+utt3LbbbfliCOOyPrrr5+LL744CxYsqPUnAQAAAAAAAAAAAAAAAAAAK5FWWdZ+5ZVXsvPOO+e0007LpEmTKiXsoiiW+bf4mTfeeCOnnXZaPve5z+Wll16q9acBAAAAAAAAAAAAAAAAAAAriVZX1r7jjjsyePDgPPvss00K2kmanJ5dFEV69eqVtddeO7169WpS0C7LMkmaFLefffbZbL/99rn11ltr+XkAAAAAAAAAAAAAAAAAAMBKor7WAT7snnvuyWGHHZaFCxc2KVonyeDBg3PooYdm++23z3bbbZe+ffsu8fzUqVPz7LPP5umnn87tt9+eZ555JkkqZe/GxsYceeSR6dy5cw466KDP7sMAAAAAAAAAAAAAAAAAAICVTqs5WXvcuHE58sgjK0Xt5IOTtA855JA8//zzeeqpp3L66adn3333/diidpL07ds3++67b04//fQ89dRTef7553PIIYc0OWl7wYIFOeqoozJ27NjP7NsAAAAAAAAAAAAAAAAAAICVT6spax9//PFpaGionKa9yiqr5J577skdd9yRLbfcsqqZW265Ze64447cfffdWWWVVZJ8UNhuaGjI8ccf35LxAQAAAAAAAAAAAAAAAACAdqZVlLUffvjhjBw5slLU7tu3b0aOHJkDDjigReZ/6UtfysiRI7PaaqtVrj3yyCN5+OGHW2Q+AAAAAAAAAAAAAAAAAADQ/rSKsvbVV1+dJCnLMkVR5Prrr892223Xou/Ybrvtcv3111fe8eH3AgAAAAAAAAAAAAAAAAAALK+al7UXLFiQe++9N0VRpCiKHHLIIS12ovZHfelLX8ohhxySsixTlmXuvffeLFiwYIW8CwAAAAAAAAAAAAAAAAAAWLnVvKz9t7/9LXPmzElZlkmSY489doW+71vf+lZlPXfu3Dz77LMr9H0AAAAAAAAAAAAAAAAAAMDKqeZl7Zdffrmy7tSpU/bdd98V+r599903nTt3TlEUS7wfAAAAAAAAAAAAAAAAAABgWdW8rD1lypTKeq211kp9ff0KfV99fX3WXnvtykneH34/AAAAAAAAAAAAAAAAAADAsqp5WbuxsTFJUhRF+vXr95m8c/XVV6+s33vvvc/knQAAAAAAAAAAAAAAAAAAwMql5mXtLl26VNbTpk37TN45ffr0yrpz586fyTsBAAAAAAAAAAAAAAAAAICVS83L2n379k2SlGWZv//97ynLcoW+b9GiRXnrrbdSFEWT9wMAAAAAAAAAAAAAAAAAACyPmpe1N95448q6sbExDz/88Ap93yOPPJLGxsZKKfzD7wcAAAAAAAAAAAAAAAAAAFhWNS9rDx48OJ07d66cdP0f//EfK/R9v/rVryrrTp06Zfvtt1+h7wMAAAAAAAAAAAAAAAAAAFZONS9rd+7cOfvss0/KskxZlrnpppvy+OOPr5B3PfbYY/nNb36ToihSFEX23nvvdO7ceYW8CwAAAAAAAAAAAAAAAAAAWLnVvKydJMcee2ySpCiKLFq0KEcddVQmTpzYou+YMGFCjjnmmEopPEm+9a1vteg7AAAAAAAAAAAAAAAAAACA9qNVlLUPPvjgDB48OMkHhe2JEydmjz32yN/+9rcWmf/ss8/m85//fF5//fXKqdrbbrttDj744BaZDwAAAAAAAAAAAAAAAAAAtD+toqydJNdcc03q6+uTfFDYfuONN7LTTjvl+9//fqZPn17VzOnTp+f73/9+Pve5z+WNN95IkpRlmfr6+lxzzTUtlh0AAAAAAAAAAAAAAAAAAGh/Wk1Ze/DgwfnFL36RsiyTfFDYXrBgQS677LKsvfbaGT58eH7729/m1Vdf/cQ5Y8eOzW9/+9sMHz48a6+9di677LIsWLAgRVFU5l522WXZfvvtV/g3AQAAAAAAAAAAAAAAAAAAK6/6Wgf4sOOOOy5z5szJKaeckuSDYnVZlpk3b17uuOOO3HHHHUmS7t27Z4011kivXr3SvXv3zJkzJ7Nmzcrbb7+dhoaGyrwPF7/LskxRFPnZz36Wb3/725/9xwEAAAAAAAAAAAAAAAAAACuVVlXWTpLvfe972WabbfL1r389b775ZuVE7MXF6yRpaGiolLIXF7E/zoefXWuttXLjjTdm7733XsFfAAAAAAAAAAAAAAAAAAAAtAd1tQ7wcYYOHZrnn38+xx9/fLp06dLkhOyP/j7pelmW6dy5c4477ri88MILitoAAAAAAAAAAAAAAAAAAECLaZVl7STp3bt3rrzyykyaNCk/+clPsv3226dDhw4py/JTf3V1dRk8eHB+8pOfZNKkSbnqqqvSp0+fWn8SAAAAAAAAAAAAAAAAAACwEqmvdYBP06dPn5x++uk5/fTTM2fOnDzxxBN56aWXMn369EyfPj2zZ89Oz54906dPn/Tp0yebbrppdt5553Tv3r3W0QEAAAAAAAAAAAAAAAAAgJVYqy9rf1j37t0zdOjQDB06tNZRAAAAAAAAAAAAAAAAAACAdq6u1gEAAAAAAAAAAAAAAAAAAADaImVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1gYAAAAAAAAAAAAAAAAAAKiCsjYAAAAAAAAAAAAAAAAAAEAVlLUBAAAAAAAAAAAAAAAAAACqoKwNAAAAAAAAAAAAAAAAAABQBWVtAAAAAAAAAAAAAAAAAACAKihrAwAAAAAAAAAAAAAAAAAAVEFZGwAAAAAAAAAAAAAAAAAAoArK2gAAAAAAAAAAAAAAAAAAAFVQ1ob/j707jdGyPh89fs0Iw66IHobgKB0CQjHGrS2JxnEBl7pB0lLUGK0BpVq1SQu2isZgtLR/9VghUqtiXGoDqaK0ki5StQSpxgWlEaTFDCCbUJ2hDp1hnfPi5Dynz7A4czHD4PD5vOK6uX/LI7795gYAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAQqf2vgDta/ny5fH+++/HmjVr4j//+U9069YtysvL4/jjj4+TTjopunTpkt67oaEhFi1aFB9++GHU1NREWVlZVFRUxPDhw2PgwIGt+CsAAAAAAAAAAAAAAAAAAODAE2sfgj7//POYPn16PP7441FdXb3X98rKyuIb3/hGfPvb344f/OAHzd5/06ZNMWXKlHjyySdjy5Yte3zntNNOizvvvDNGjRrV4vsDAAAAAAAAAAAAAAAAAMDBoLS9L8CB9dJLL8XgwYNj8uTJ+wy1IyK2bdsWCxcujKlTpzZ7/9deey2GDRsWDz/88F5D7YiId955J0aPHh3XXHNNbNu2rdn7AwAAAAAAAAAAAAAAAADAwcKXtQ8hDz74YPzoRz+KxsbGouddu3aN/v37x9FHHx319fWxfv36+Ne//tXi/RcuXBgXXXRR1NfXFz3v3bt3VFZWRk1NTXz88cexc+fOwt89/fTTUVdXF88991yUlJTkfhgAAAAAAAAAAAAAAAAAALQDX9Y+RMycOTN++MMfFoXa3/zmN+MPf/hD1NbWxkcffRRvvvlmLFmyJDZt2hRr166NZ555Jr71rW9FWVnZF+5fU1MTY8eOLQq1BwwYEC+++GJ89tln8e6770Z1dXWsXLkyJkyYULR2zpw58eCDD7bejwUAAAAAAAAAAAAAAAAAgAPAl7UPAStWrIibbrqpMHfu3DmeeuqpuOKKK/a6pn///nHVVVfFVVddFTU1NV94xn333Rfr1q0rzJWVlbFw4cLo379/0XsVFRXxyCOPxHHHHReTJ08uPL/77rvj2muvjSOPPLIlPw0AAAAAAAAAAAAAAAAAANqNL2sfAq6//vpoaGgozM8+++w+Q+2mviig3rRpU0yfPr3o2WOPPbZbqP3fbrvttqiqqirMmzdvjvvvv7/ZdwIAAAAAAAAAAAAAAAAAgPYm1u7g5s6dG6+++mphHjNmTIwZM6ZVz5g1a1bU1dUV5qqqqhgxYsQ+15SUlMRdd91V9OyJJ56IxsbGVr0bAAAAAAAAAAAAAAAAAAC0FbF2B/foo48WzU0D6dYwd+7conncuHHNWnfOOedEZWVlYd6wYUO88cYbrXo3AAAAAAAAAAAAAAAAAABoK2LtDmzt2rXxpz/9qTCffPLJccIJJ7TqGXV1dbFgwYKiZ+eff36z1paUlMTIkSOLnr300kutdjcAAAAAAAAAAAAAAAAAAGhLYu0O7I9//GPs3LmzMJ9zzjmtfsYHH3wQ27dvL8yVlZXRr1+/Zq8/44wziub33nuvta4GAAAAAAAAAAAAAAAAAABtSqzdgb311ltF80knnVT48+LFi+OWW26Jk046KY488sjo3r17fOUrX4nzzjsv7r///li7dm2zzli2bFnRPGzYsBbdsen7TfcDAAAAAAAAAAAAAAAAAICDlVi7A2saaw8cODDq6upi3Lhxceqpp8b06dNjyZIlUVtbG/X19bFq1aqYP39+TJo0KQYPHhy333570Vez92T58uVF87HHHtuiOzZ9f9WqVdHQ0NCiPQAAAAAAAAAAAAAAAAAAoD10au8L0HZWrFhRNJeWlkZVVVUsXrz4C9fW19fH1KlT46233oo5c+ZEr1699vjexo0bi+aKiooW3bG8vDw6deoUO3bsiIiIXbt2xaeffhrHHHNMi/bZ0702bdrUojVN/3sBAAAAAAAAAAAAAAAAAMC+iLU7qF27dsXnn39e9OyWW24phNolJSVxySWXxEUXXRQVFRWxZcuWWLx4cTzzzDOxbt26wpr58+fHd7/73Xj++ef3eE5dXV3R3KNHjxbds6SkJLp161Z016Z7ZsyYMSOmTJmy3/sAAAAAAAAAAAAAAAAAAMDeiLU7qM2bN0djY2PRs3fffTciIo466qh44YUX4swzzyz6+7Fjx8Ydd9wREyZMiN/85jeF53PmzImnn346rr766t3OaRpWd+3atcV3bYtYGwAAAAAAAAAAAAAAAAAA2lppe1+AtrG34Pmwww6LefPm7RZq/z89e/aMZ555Js4///yi5z/96U93i78jIhoaGormsrKyFt+1S5cuRXN9fX2L9wAAAAAAAAAAAAAAAAAAgAPNl7U7qL194Xr8+PExfPjwfa4tLS2NX/7ylzF48ODYtWtXREQsX748/vrXv8bZZ5+9z3O2bdvW4rtu3bp1n3tm3HjjjTFmzJgWrVmxYkWMHj16v88GAAAAAAAAAAAAAAAAAODQINbuoHr27LnH59ddd12z1g8cODBGjhwZf/7znwvP9hRrNz2n6Ze2m6Ppl7T3dveW6Nu3b/Tt23e/9wEAAAAAAAAAAAAAAAAAgL0pbe8L0Da6desWhx12WNGzXr16xSmnnNLsPc4666yi+e23397tnaZh9ZYtW1pwy4jGxsY2ibUBAAAAAAAAAAAAAAAAAKCtibU7sKZflh40aFCUljb/n3zIkCFF88aNG7/wjDVr1rTghhGffPJJ7NixozCXlpbG0Ucf3aI9AAAAAAAAAAAAAAAAAACgPYi1O7CvfvWrRfPhhx/eovVN36+pqdntnaZB9+rVq1t0RtP3BwwYEF27dm3RHgAAAAAAAAAAAAAAAAAA0B7E2h3YsGHDiuatW7e2aH1DQ0PR3L17993eGTp0aNG8dOnSFp2xbNmyfe4HAAAAAAAAAAAAAAAAAAAHK7F2B3bqqacWzZ988kmL1m/cuLFoPuqoo3Z754QTTojOnTsX5pUrV8b69eubfcbrr79eNJ988sktuiMAAAAAAAAAAAAAAAAAALQXsXYHdvHFF0dp6f//J66uro7PPvus2evfeeedonnIkCG7vdOrV6+oqqoqevbyyy83a//GxsaYP39+0bNLL7202fcDAAAAAAAAAAAAAAAAAID2JNbuwPr27RtnnHFG0bM5c+Y0a+2OHTvihRdeKHp29tln7/Hdyy67rGieOXNms8549dVXo7q6ujCXl5fH8OHDm7UWAAAAAAAAAAAAAAAAAADam1i7g5swYULRfN9998XWrVu/cN1jjz0WGzZsKMyHH354XHDBBXt89/LLL48ePXoU5gULFsQrr7yyz/0bGxtjypQpRc+uvfbaoi+BAwAAAAAAAAAAAAAAAADAwUwZ28FdccUVceKJJxbmf/zjHzFhwoTYtWvXXte8+eabceuttxY9u/HGG+OII47Y4/t9+/aNm266qejZ+PHjY926dXs9Y+rUqbFgwYLCfMQRR8SkSZP2+VsAAAAAAAAAAAAAAAAAAOBg0qm9L0DbKi0tjQcffDDOO++8aGxsjIiIp556KtauXRs/+9nP4rTTTiu8u3nz5pg5c2bcddddUVdXV3h+/PHHx+23377Pc2699dZ46qmnCl/jrq6ujtNPPz2mTZsWl156aZSUlERExJo1a+Kee+6JX/3qV0XrJ0+eHH369GmV3wwAABzcvvKTee19BfbTyp9d3N5XAAAAAAAAAAAAAAA4KIi1DwEjRoyIqVOnxk9+8pPCs/nz58fXvva16NevX1RUVMSWLVvio48+im3bthWtPeqoo+K5556LXr167fOMPn36xOzZs+OCCy6IhoaGiIhYtWpVjBo1Knr37h2VlZVRW1sbq1evjp07dxatHTVqVEycOLGVfi0AAAAAAAAAAAAAAAAAABwYpe19AQ6MH//4xzFt2rTo3Llz0fMNGzbE22+/HcuWLdst1B4yZEj87W9/ixNPPLFZZ1RVVcW8efN2+0J2bW1tLF68OKqrq3cLta+88sqYPXt24cvbAAAAAAAAAAAAAAAAAADwZSHWPoTcfPPNsWTJkhg7duxu0fZ/q6ysjIceeiiWLFkSgwcPbtEZ5557bixdujRuuOGG6N69+17fO+WUU+L555+PZ599Nrp06dKiMwAAAAAAAAAAAAAAAAAA4GDQqb0vwIE1dOjQmDVrVvz73/+ORYsWxT//+c/YvHlz9OzZM8rLy+PUU0+NIUOG7NcZ5eXlMWPGjHjggQdi0aJFsWzZsqitrY2ysrI45phjYvjw4TFo0KBW+kUAAAAAAAAAAAAAAAAAANA+xNqHqMMPPzwuvPDCuPDCC9vsjG7dusWIESNixIgRbXYGAAAAAAAAAAAAAAAAAAC0l9L2vgAAAAAAAAAAAAAAAAAAAMCXkVgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgoVN7XwAAAAD4cvnKT+a19xWaZfCmVfHyF7xz3v/+a/zzf608ENc5qKz82cXtfQUAAAAAAAAAAAAA6BB8WRsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJHRq7wvQMTU0NMSiRYviww8/jJqamigrK4uKiooYPnx4DBw4sL2vBwAAAAAAAAAAAAAAAAAA+02sTVxxxRUxa9asomcDBgyIlStXtnivTZs2xZQpU+LJJ5+MLVu27PGd0047Le68884YNWpU5roAAAAAAAAAAAAAAAAAAHBQKG3vC9C+fv/73+8Wame99tprMWzYsHj44Yf3GmpHRLzzzjsxevTouOaaa2Lbtm2tcjYAAAAAAAAAAAAAAAAAABxovqx9CNu8eXPccMMNrbLXwoUL46KLLor6+vqi5717947KysqoqamJjz/+OHbu3Fn4u6effjrq6uriueeei5KSkla5BwAAAAAAAAAAAAAAAAAAHCi+rH0ImzRpUqxduzYiInr06JHep6amJsaOHVsUag8YMCBefPHF+Oyzz+Ldd9+N6urqWLlyZUyYMKFo7Zw5c+LBBx9Mnw0AAAAAAAAAAAAAAAAAAO1FrH2Ieu211+Lxxx+PiIjS0tK466670nvdd999sW7dusJcWVkZixYtilGjRhV9MbuioiIeeeSRuPfee4vW33333VFTU5M+HwAAAAAAAAAAAAAAAAAA2oNY+xBUX18f48ePj8bGxoiIuPnmm+PrX/96aq9NmzbF9OnTi5499thj0b9//72uue2226Kqqqowb968Oe6///7U+QAAAAAAAAAAAAAAAAAA0F7E2oegO++8Mz766KOIiDjuuOPinnvuSe81a9asqKurK8xVVVUxYsSIfa4pKSnZ7UveTzzxRCEeBwAAAAAAAAAAAAAAAACALwOx9iHmrbfeil/84heF+eGHH46ePXum95s7d27RPG7cuGatO+ecc6KysrIwb9iwId544430PQAAAAAAAAAAAAAAAAAA4EATax9Ctm/fHuPGjYudO3dGRMSYMWPikksuSe9XV1cXCxYsKHp2/vnnN2ttSUlJjBw5sujZSy+9lL4LAAAAAAAAAAAAAAAAAAAcaGLtQ8jUqVPj73//e0RE9O7dO6ZNm7Zf+33wwQexffv2wlxZWRn9+vVr9vozzjijaH7vvff26z4AAAAAAAAAAAAAAAAAAHAgibUPEUuXLo177723MP/85z9vUVi9J8uWLSuahw0b1qL1Td9vuh8AAAAAAAAAAAAAAAAAABzMxNqHgF27dsW4ceNi27ZtERFx5plnxnXXXbff+y5fvrxoPvbYY1u0vun7q1atioaGhv2+FwAAAAAAAAAAAAAAAAAAHAhi7UPAtGnT4o033oiIiLKysnj00UejpKRkv/fduHFj0VxRUdGi9eXl5dGpU6fCvGvXrvj000/3+14AAAAAAAAAAAAAAAAAAHAgdPriV/gyq66ujjvuuKMw33bbbTF06NBW2buurq5o7tGjR4vWl5SURLdu3eLzzz/f655ZGzdujE2bNrVozYoVK1rlbAAAAAAAAAAAAAAAAAAADg1i7Q7u+uuvjy1btkRExNChQ+P2229vtb2bhtVdu3Zt8R5tFWvPmDEjpkyZ0ip7AQAAAAAAAAAAAAAAAADAnpS29wVoOzNnzoz58+dHxP/9ivWjjz4aZWVlrbZ/Q0ND0ZzZu0uXLkVzfX39ft0JAAAAAAAAAAAAAAAAAAAOFLF2B7V+/fqYOHFiYR4/fnyceeaZrXpG0y9pb9u2rcV7bN26dZ97AgAAAAAAAAAAAAAAAADAwapTe1+AtvH9738/amtrIyKiX79+8T//8z+tfkbPnj2L5qZf2m6Opl/Sbrpn1o033hhjxoxp0ZoVK1bE6NGjW+V8AAAAAAAAAAAAAAAAAAA6PrF2B/Tb3/42XnjhhcL80EMPRe/evVv9nKZh9ZYtW1q0vrGxsc1i7b59+0bfvn1bZS8AAAAAAAAAAAAAAAAAANiT0va+AK1v0qRJhT9ffPHF8Z3vfKdNzmkaQ69Zs6ZF6z/55JPYsWNHYS4tLY2jjz66Ve4GAAAAAAAAAAAAAAAAAABtzZe1O6Da2trCn+fNmxclJSUt3mPVqlW7rVu8eHGcfPLJhXnIkCFFf7969eoWndH0/QEDBkTXrl1bdlEAAAAAAAAAAAAAAAAAAGgnvqxN2tChQ4vmpUuXtmj9smXL9rkfAAAAAAAAAAAAAAAAAAAczMTapJ1wwgnRuXPnwrxy5cpYv359s9e//vrrRfN/f7UbAAAAAAAAAAAAAAAAAAAOdp3a+wK0vrlz58b27dtbtOb999+PiRMnFuby8vL49a9/XfTOoEGDiuZevXpFVVVV/OUvfyk8e/nll+Pqq6/+wvMaGxtj/vz5Rc8uvfTSFt0ZAAAAAAAAAAAAAAAAAADak1i7AzrrrLNavKZTp+L/Fbp27RojR478wnWXXXZZUaw9c+bMZsXar776alRXVxfm8vLyGD58eAtuDAAAAAAAAAAAAAAAAAAA7au0vS/Al9vll18ePXr0KMwLFiyIV155ZZ9rGhsbY8qUKUXPrr322igt9b8jAAAAAAAAAAAAAAAAAABfHupY9kvfvn3jpptuKno2fvz4WLdu3V7XTJ06NRYsWFCYjzjiiJg0aVKb3REAAAAAAAAAAAAAAAAAANqCWJv9duutt0a/fv0Kc3V1dZx++unxu9/9LhobGwvP16xZE9/73vdi8uTJResnT54cffr0OWD3BQAAAAAAAAAAAAAAAACA1tCpvS/Al1+fPn1i9uzZccEFF0RDQ0NERKxatSpGjRoVvXv3jsrKyqitrY3Vq1fHzp07i9aOGjUqJk6c2B7XBgAAAAAAAAAAAAAAAACA/eLL2rSKqqqqmDdv3m5fyK6trY3FixdHdXX1bqH2lVdeGbNnz46SkpIDeVUAAAAAAAAAAAAAAAAAAGgVYm1azbnnnhtLly6NG264Ibp3777X90455ZR4/vnn49lnn40uXbocwBsCAAAAAAAAAAAAAAAAAEDr6dTeF+DgcPbZZ0djY+N+71NeXh4zZsyIBx54IBYtWhTLli2L2traKCsri2OOOSaGDx8egwYNaoUbAwAAAAAAAAAAAAAAAABA+xJr0ya6desWI0aMiBEjRrT3VQAAAAAAAAAAAAAAAAAAoE2UtvcFAAAAAAAAAAAAAAAAAAAAvozE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAAAAAJAg1gYAAAAAAAAAAAAAAAAAAEgQawMAAAAAAAAAAAAAAAAAACSItQEAAAAAAAAAAAAAAAAAABLE2gAAAAAAAAAAAAAAAAAAAAlibQAAAAAAAAAAAAAAAAAAgASxNgAAAAAAAAAAAAAAAAAAQIJYGwAAAAAAAAAAAAAAAAAAIEGsDQAAAAAAAAAAAAAAAAAAkCDWBgAAAAAAAAAAAAAAAAAASBBrAwAAAAAAAAAAAAAAAAAAJIi1AQAAAAAAAAAAAAAAAAAAEsTaAAAAAAAAAAAAAAAAAAAACWJtAAAAAAAAAAAAAAAAAACABLE2AAAAAAAAAAAAAAAAAABAglgbAAAAAAAAAAAAAAAAAAAgQawNAAAAAAAAAAAAAAAAAACQINYGAAAAAAAAAAAAAAAAAABIEGsDAAAAAAAAAAAAAAAAAAAkiLUBAAAAAAAAAAAAAAAAAAASxNoAAAAAAAAAAAAAAAAAAAAJYm0AAAAAAAAAAAAAAAAAAIAEsTYAAAAAAAAAAAAAAAAAAECCWBsAAAAAAAAAAAAAAAAAACBBrA0AAAAAAAAAAAAAAADA/2HvXoOzLM8Ejl8hB4OhAnKwgtB4YArWqVaL08IacFy2rahFZzx1ugPKzq6lo2XVQty1WGo7ok4RnVanOyDddukqpRa7xq5H0Fa6HFTUClI5GQLuhiBCOAY32Q/dvu0bTsn9JnkD+f2+3Xee57kv/KAPI38eACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACBBUb4HAAAAAKBjlVdW5XsEcrBxxth8jwAAAAAAAAAAAADA//NlbQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARF+R4AAAAAAKArKa+syvcI5GjjjLH5HgEAAAAAAAAAAIBOwpe1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEhTlewAAAAAAAICOUl5Zle8RyNHGGWPzPQIAAAAAAAAAAGT4sjYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAECConwPQMdoamqKjRs3xltvvRU1NTXx4YcfxgknnBC9e/eOIUOGxPDhw6O0tLRNz6yvr49XXnkl/vCHP8TOnTuje/fu8YlPfCJGjBgRAwYMaNOzAAAAAAAAAAAAAAAAAACgo4m1j2Pbt2+PhQsXxn/+53/Giy++GHV1dYe9tri4OMaOHRuTJ0+OUaNG5XTuhg0bYtq0aTF//vxoaGg46OcFBQUxatSomD59elRUVOR0FgAAAAAAAAAAAAAAAAAA5Eu3fA9A+/j6178eH//4x+PGG2+M+fPnHzHUjog4cOBALFy4MEaPHh3jx4+PnTt3Jp07f/78OOecc+Lf/u3fDhlqR/zxK9+LFy+O0aNHR2VlZTQ1NSWdBQAAAAAAAAAAAAAAAAAA+eTL2seppUuXHjKWLiwsjFNPPTVOOeWUOHDgQLz33nuxY8eOrGt+8pOfxDvvvBMvvPBC9OjRo8Vn/vznP4/rr78+Ghsbs/b79esXgwYNitra2ti8eXMmzm5qaop777039u/fHw888EDCrxIAAAAAAAAAAAAAAAAAAPLHl7W7gF69esWkSZOiqqoqtm/fHps2bYoVK1bEG2+8Edu2bYtFixbFRRddlHXPsmXLYsKECS0+Y926dXHDDTdkhdrnnntuvPjii1FbWxuvvvpqbNq0KVavXh1XXXVV1r2zZs2KJ554IqdfIwAAAAAAAAAAAAAAAAAAdDSx9nGsvLw8Zs+eHVu2bIkf/vCHcemll8bHPvaxrGsKCwtj9OjRsWjRovj7v//7rJ/94he/iEWLFrXorG9961uxe/fuzHr48OHx8ssvx8UXX5x13Sc/+clYsGDBQWdNmTIlPvroo9b88gAAAAAAAAAAAAAAAAAAIK/E2sep6dOnx5o1a2LixInRvXv3o15fWFgYDz/8cHz2s5/N2p89e/ZR73377bfj8ccfz6xLSkriX//1X+Okk0465PUFBQXx4IMPxpAhQzJ769ati7lz5x71LAAAAAAAAAAAAAAAAAAA6CzE2sepsWPHRklJSavuKSwsjClTpmTtPfPMM0e979FHH43GxsbM+rrrrothw4Yd8Z7S0tKorKzM2mtJGA4AAAAAAAAAAAAAAAAAAJ2FWJssF110UdZ627ZtsWfPniPe86tf/SprPXHixBadde2110ZZWVlmvXz58tiyZUsLJwUAAAAAAAAAAAAAAAAAgPwSa5Old+/eB+3t2LHjsNevWbMm1q5dm1mXlZXFiBEjWnRW82ubmpqiqqqqFdMCAAAAAAAAAAAAAAAAAED+iLXJsnnz5oP2+vTpc9jrV65cmbW+8MILo6ioqMXnjRw58ojPAwAAAAAAAAAAAAAAAACAzkqsTZbf/OY3WetPfOITUVJSctjrV69enbU+++yzW3Ve8+ubPw8AAAAAAAAAAAAAAAAAADorsTZZHn300az1pZdeesTr16xZk7UeNGhQq85rfn3z5wEAAAAAAAAAAAAAAAAAQGdVlO8B6DyefvrpePnll7P2JkyYcMR7amtrs9annXZaq84cOHBg1nrr1q2tuv9wamtrW/2stWvXtsnZAAAAAAAAAAAAAAAAAAB0DWJtIiLigw8+iH/4h3/I2hs3blxceOGFR7xv165dWeuysrJWndv8+gMHDsT+/fvjhBNOaNVzmnv44Ydj+vTpOT0DAAAAAAAAAAAAAAAAAACORKxNNDY2xle/+tWoqanJ7PXs2TMeeuiho97bPNYuLS1t1dndu3c/5DNzjbUBAAAAjlfllVX5HgEAAAAAAAAAAACA/9ct3wOQf9/85jfj17/+ddbej370oxg0aNBR7923b1/WuqSkpFVnHyrK3rt3b6ueAQAAAAAAAAAAAAAAAAAA+eDL2l3cQw89FDNnzszamzJlSlx77bUtur/5l7QbGhpadf7+/fuP+swUkyZNiquvvrpV96xduzbGjRuX89kAAAAAAAAAAAAAAAAAAHQNYu0u7Gc/+1lMnjw5a2/ChAkxY8aMFj+jR48eWevmX9o+mkN9Rbv5M1P0798/+vfvn/NzAAAAAAAAAAAAAAAAAADgcLrlewDy46mnnorx48dHU1NTZu+qq66K2bNnR0FBQYuf0zys3r17d6vmaH59UVFRm3xZGwAAAAAAAAAAAAAAAAAA2ptYuwtatGhRXH311fHRRx9l9saMGRP//u//HoWFha16VvOvV9fU1LTq/s2bN2et+/Xr16r7AQAAAAAAAAAAAAAAAAAgX8TaXczSpUvjiiuuiH379mX2RowYEb/85S+jpKSk1c/75Cc/mbWurq5u1f3Nrx86dGirZwAAAAAAAAAAAAAAAAAAgHwQa3chb775ZnzpS1+KXbt2ZfY+85nPxNNPPx1lZWVJz2weV69atapV969evfqIzwMAAAAAAAAAAAAAAAAAgM5KrN1FrFmzJsaMGRPbt2/P7A0bNiyeeeaZ6NmzZ/JzzzvvvKz18uXL46OPPmrx/a+88soRnwcAAAAAAAAAAAAAAAAAAJ2VWLsLeO+99+Kv//qvo7a2NrN3+umnx3PPPRf9+vXL6dlDhw6NM888M7PevXt3LFmypEX37t69O373u99l1gUFBXHZZZflNA8AAAAAAAAAAAAAAAAAAHQUsfZx7v33349LLrkkampqMnsDBw6MF154IQYOHNgmZ1xxxRVZ6zlz5rTovscffzx27dqVWX/2s5+NAQMGtMlMAAAAAAAAAAAAAAAAAADQ3sTax7EPPvggxowZE+vWrcvs9evXL5577rk4/fTT2+ycG2+8MQoKCjLrxx57LFavXn3Ee/bt2xczZszI2ps4cWKbzQQAAAAAAAAAAAAAAAAAAO1NrH2cqq+vjy9+8Yvx9ttvZ/Z69eoVzz77bAwbNqxNzzrnnHPimmuuyawbGhpi/PjxsXPnzkNe39TUFJMnT4533303s3fGGWfEjTfe2KZzAQAAAAAAAAAAAAAAAABAeyrK9wC0jyuuuCKWL1+etXfrrbdGXV1dPP/886161gUXXBC9e/c+4jXf/e534z/+4z9iz549ERGxfPnyqKioiFmzZsXo0aMz1/3hD3+IO+64I5544oms+2fMmBHFxcWtmgsAAAAAAAAAAAAAAAAAAPJJrH2cWrx48UF706ZNS3rWokWLsoLrQznrrLNizpw58ZWvfCWampoiIuKNN96Iiy++OPr16xeDBw+O2traqKmpyfz8T26++ea4+uqrk2YDAAAAAAAAAAAAAAAAAIB8EWvTZq677rpoamqKiRMnxt69ezP7W7duja1btx7ynttvvz3uu+++jhoRAAAAAAAAAAAAAAAAAADaTLd8D8Dx5frrr4/f//738ZWvfCWKi4sPe11FRUUsXrw47r///igoKOjACQEAAAAAAAAAAAAAAAAAoG34svZxqqmpKW9nn3HGGTFv3rx45JFH4re//W28++67UV9fH6WlpTF48OAYOXJkDBw4MG/zAQAAAAAAAAAAAAAAAABAWxBr025OOumkuPTSS/M9BgAAAAAAAAAAAAAAAAAAtItu+R4AAAAAAAAAAAAAAAAAAADgWCTWBgAAAAAAAAAAAAAAAAAASCDWBgAAAAAAAAAAAAAAAAAASCDWBgAAAAAAAAAAAAAAAAAASCDWBgAAAAAAAAAAAAAAAAAASCDWBgAAAAAAAAAAAAAAAAAASCDWBgAAAAAAAAAAAAAAAAAASCDWBgAAAAAAAAAAAAAAAAAASFCU7wEAAAAAAACgpcorq/I9AjnaOGNsvkcAAAAAAAAAAGgzvqwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQQKwNAAAAAAAAAAAAAAAAAACQoCjfAwAAAAAAAABdR3llVb5HIEcbZ4zN9wgAAAAAAAAA0Gn4sjYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAEACsTYAAAAAAAAAAAAAAAAAAECConwPAAAAAAAAx5Lyyqp8jwAAAAAAAAAAAEAn4cvaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACcTaAAAAAAAAAAAAAAAAAAAACYryPQAArVNeWZXvEQAAAAAAAAAAAAAAAACA8GVtAAAAAAAAAAAAAAAAAACAJGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABGJtAAAAAAAAAAAAAAAAAACABEX5HgAAAAAAAAAAAACgJcorq/I9AjnaOGNsvkcAAAAAgDbly9oAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJxNoAAAAAAAAAAAAAAAAAAAAJivI9AAAAAAAAAADHjvLKqnyPAF3axhlj8z0CAAAAAAAA8Bd8WRsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACCBWBsAAAAAAAAAAAAAAAAAACBBUb4HAAAAAAAAAACArqK8sirfI5CjjTPG5nsEAAAAAACgE/FlbQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARibQAAAAAAAAAAAAAAAAAAgARF+R4AAAAAAAAAAICWKa+syvcIAMc0/x4FAAAAAKCt+bI2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAArE2AAAAAAAAAAAAAAAAAABAgqJ8DwAAAAAAAAAAAHCsKK+syvcIAAAA5InfEx77Ns4Ym+8RAIDjkC9rAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJCjK9wAAAAAAAAAAAAAAQOdXXlmV7xHI0cYZY/M9AgAAABx3fFkbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAgQVG+BwAAAAAAAAAAAACgayivrMr3CAAAwDHM7ymOfRtnjM33CABtzpe1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEoi1AQAAAAAAAAAAAAAAAAAAEhTlewAAAAAAAAAAAAAAANpfeWVVvkeALm/jjLH5HgG6NP8tBADagy9rAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJBBrAwAAAAAAAAAAAAAAAAAAJCjK9wAc39atWxfLli2LmpqaaGhoiN69e8fQoUNjxIgRUVpamu/xAAAAAAAAAAAAAAAAAAAgmVibdrFw4cK4++6747XXXjvkz3v06BETJkyIu+66K/r27dvB0wEAAAAAAAAAAAAAAAAAQO7E2rSp/fv3x8SJE2PevHlHvG7Xrl3xgx/8IB5//PFYsGBBVFRUdNCEAAAAAAAAAAAAAACQH+WVVfkeAQDyyn8Lj20bZ4zN9wjQKXXL9wAcPxobG+Paa689KNQuLCyM008/Pc4777zo2bNn1s+2bt0aX/rSl+J3v/tdR44KAAAAAAAAAAAAAAAAAAA5E2vTZu6///548skns/ZuuummqK6ujvXr18frr78eH3zwQTzxxBMxePDgzDV79uyJa665Jnbs2NHRIwMAAAAAAAAAAAAAAAAAQDKxNm1i27Zt8b3vfS9r75577olHHnkkBgwYkNnr1q1bXHnllbFkyZIoLy/P7NfU1MTMmTM7alwAAAAAAAAAAAAAAAAAAMiZWJs2cd9990V9fX1mXVFREVOnTj3s9QMHDozZs2dn7T3wwAOxbdu2dpsRAAAAAAAAAAAAAAAAAADaklibnDU2NsbcuXOz9r797W9HQUHBEe+75JJL4qKLLsqs6+vrY/78+e0yIwAAAAAAAAAAAAAAAAAAtDWxNjlbsmRJbN26NbM+44wzYvTo0S26d+LEiVnrhQsXtuFkAAAAAAAAAAAAAAAAAADQfsTa5KyqqiprPWbMmKN+Vfsvr/1Lixcvjt27d7fZbAAAAAAAAAAAAAAAAAAA0F7E2uRs5cqVWesRI0a0+N4BAwZEeXl5Zt3Q0BCrVq1qo8kAAAAAAAAAAAAAAAAAAKD9iLXJ2erVq7PWZ599dqvub3598+cBAAAAAAAAAAAAAAAAAEBnJNYmJ3v37o3q6uqsvUGDBrXqGc2vX7NmTc5zAQAAAAAAAAAAAAAAAABAeyvK9wAc2+rq6qKpqSmzLi4ujv79+7fqGQMHDsxa19bW5jxXbW1tbN26tVX3rFq1Kmu9du3anOeA9tCw9b18jwAAAMeEXdu3xNstuKahQ6YBAAAAAAAAAAAAOLa9/fbR/mQm5EfzHnT//v0der5Ym5zs2rUra33iiSdGQUFBq55RVlZ2xGemePjhh2P69Ok5PWPcuHE5zwEAAED+vB8R5xztol9+rwMmAQAAAAAAAAAAADj2nfNovieAltm0aVOcf/75HXZetw47ieNS87C6tLS01c/o3r37EZ8JAAAAAAAAAAAAAAAAAACdkVibnOzbty9rXVJS0upnnHDCCVnrvXv35jQTAAAAAAAAAAAAAAAAAAB0hKJ8D8CxrfmXtBsaGlr9jP379x/xmSkmTZoUV199davu2blzZ6xYsSJOOumk6NWrVwwaNOigkLytrV27NsaNG5dZL1y4MM4666x2PRMAADgy7+kAAND5eE8HAIDOybs6AAB0Pt7TAQDoivbv3x+bNm3KrEeNGtWh54u1yUmPHj2y1s2/tN0Szb+k3fyZKfr37x/9+/dv9X2f//zncz47F2eddVZ86lOfyusMAABANu/pAADQ+XhPBwCAzsm7OgAAdD7e0wEA6CrOP//8vJ3dLW8nc1xoHlbv2bMnmpqaWvWM3bt3H/GZAAAAAAAAAAAAAAAAAADQGYm1yUnfvn2joKAgsz5w4EDU1ta26hmbN2/OWqd8ERsAAAAAAAAAAAAAAAAAADqaWJucdO/ePQYPHpy1V11d3apnNL9+6NChOc8FAAAAAAAAAAAAAAAAAADtTaxNzprH1atWrWrV/atXrz7i8wAAAAAAAAAAAAAAAAAAoDMSa5Oz8847L2u9ZMmSFt/7/vvvx8aNGzPr4uLiOPvss9toMgAAAAAAAAAAAAAAAAAAaD9ibXJ22WWXZa2ff/75aGpqatG9zz77bNb64osvjh49erTZbAAAAAAAAAAAAAAAAAAA0F7E2uRsxIgR0bdv38x6/fr1sXjx4hbdO2fOnKz1l7/85bYcDQAAAAAAAAAAAAAAAAAA2o1Ym5x169YtJkyYkLU3ffr0o35d+4UXXojf/OY3mfXHPvaxuOaaa9pjRAAAAAAAAAAAAAAAAAAAaHNibdrE1KlTo0ePHpn1Sy+9FPfee+9hr9+8eXP83d/9XdbeN77xjawvdAMAAAAAAAAAAAAAAAAAQGcm1qZN9O3bN/7pn/4pa++OO+6ISZMmxZYtWzJ7jY2NsXDhwhgxYkRs3Lgxsz9gwIC47bbbOmpcAAAAAAAAAAAAAAAAAADImVibNjN16tS47LLLsvYeeeSRGDx4cJx55plx/vnnR58+feLKK6+M6urqzDXdu3eP+fPnR69evTp4YgAAAAAAAAAAAAAAAAAASFeU7wE4fnTr1i1+/vOfxw033BCPPfZYZv9///d/Y/369Ye8p0+fPrFgwYIYOXJkR43ZqfTr1y/uuuuurDUAAJBf3tMBAKDz8Z4OAACdk3d1AADofLynAwBAxytoampqyvcQHH9+8YtfxHe/+91YuXLlIX9eVlYW48ePj7vuuiv69+/fscMBAAAAAAAAAAAAAAAAAEAbEGvTrtauXRtLly6NzZs3R0NDQ/Tq1SuGDRsWI0eOjNLS0nyPBwAAAAAAAAAAAAAAAAAAycTaAAAAAAAAAAAAAAAAAAAACbrlewAAAAAAAAAAAAAAAAAAAIBjkVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAggVgbAAAAAAAAAAAAAAAAAAAgQVG+B4B8WLduXSxbtixqamqioaEhevfuHUOHDo0RI0ZEaWlp3uZqamqK1157LVauXBm1tbUREXHKKafEueeeG+eff34UFBTkfMbWrVvjrbfeinXr1sX27dujqakpevfuHaeddlp87nOfi5NPPjnnMwAAIFVXflcHAIDOynv6n/33f/93LF++PDZs2BD19fVRXFwcJ598cpx11llx7rnnRu/evdv8TAAAOJSu/p7e2NgY77zzTqxcuTLq6uqivr4+TjzxxDj55JPjnHPOiU9/+tNRXFzcJmcBAEBLddb39I60bdu2eOWVV2LdunWxe/fuKCsrizPPPDNGjhwZffr0yfd4AADQbsTadCkLFy6Mu+++O1577bVD/rxHjx4xYcKEuOuuu6Jv374dNteBAwfiwQcfjFmzZsXmzZsPec1pp50WkydPjltuuaVV/zOpoaEhnnnmmaiqqooXXngh1q5de9hrCwoKYvjw4XHzzTfHddddF0VF/hUBAEDH6Irv6i31ox/9KG666aaD9jds2BDl5eVtfh4AAPyJ9/Q/amxsjHnz5sUPf/jDWLp06WGvKygoiLPPPjvGjh0b//zP/xwnnXRSTucCAMChdPX39C1btsSsWbNi7ty5UVdXd9jrysrK4vrrr49bb701hg0blnQWAAC0VGd8T29qaop33nknli1bFsuWLYulS5fGm2++GQcOHMhcM378+Pjxj3/cJue98cYbMW3atHjqqaeisbHxoJ8XFhbG2LFj4+67745Pf/rTbXImAAB0JgVNTU1N+R4C2tv+/ftj4sSJMW/evBZd369fv1iwYEFUVFS082QRmzZtii9/+cvx+uuvt+j6Cy64IJ588skYOHDgUa/98Y9/HLfeemts37691XMNHz485s2bF0OGDGn1vQAA0FJd9V29pWpqauJTn/pU7Ny586CfibUBAGgv3tP/7J133omvfvWr8eqrr7bqvtWrV8fQoUOTzgQAgEPxnh7x2GOPxde+9rX48MMPW3xPSUlJfOc734mpU6e26iwAAGiJzviePnfu3Jg3b16sWLEiduzYccRr2yrWfvDBB+P222+Pjz766KjXFhUVxcyZM+Pmm2/O+VwAAOhMxNoc9xobG+Oqq66KJ598Mmu/sLAwBg8eHD179owNGzYc9JvRE088MZ5//vn4/Oc/326z1dbWxogRI2LdunVZ+927d48zzjgjGhsbY8OGDbFv376snw8ZMiSWLFly1L9Z7fbbb4/vf//7h/xZ//7945RTTomSkpLYsmVLvP/++wdd07dv33j55Zf9DcMAALSLrvyu3lKXX355PPXUU4f8mVgbAID24D39z1566aW44oorDvrLkwoLC2PAgAHRv3//aGxsjLq6uti0aVPWNWJtAADakvf0iJ/+9Kcxfvz4aP5H3QoLC2PIkCHRs2fPqK+vj3fffTfrS4F/cuedd8bdd9/dyl8dAAAcXmd9Tx83btxBMx1OW8TaM2fOjNtuu+2g/VNPPTUGDBhw2D+n/uCDD8Ytt9yS09kAANCZdMv3ANDe7r///oN+w3nTTTdFdXV1rF+/Pl5//fX44IMP4oknnojBgwdnrtmzZ09cc801R/0bxXIxYcKErP9ZVVpaGrNmzYq6urr4/e9/H6tWrYq6urqYOXNmlJaWZq57991348Ybb2zVWcXFxXHllVfGvHnzYvPmzfE///M/8eabb8aKFStiy5YtsXr16rjhhhuy7qmrq4svfvGLsWfPntx+oQAAcAje1Y/sZz/7WSbULisra5NnAgDA0XhP/6M33ngjLr/88qxQe9iwYfHTn/40amtro7q6OlasWBGvvfZaVFdXx44dO+Lpp5+Or33ta9GrV6+cf60AAPCXuvp7enV1ddx0001ZoXbv3r3j4Ycfjg8//DBWr14d//Vf/xVvv/127Ny5M37yk5/EqaeemvWM733ve/Hb3/42x18tAAD8WWd+Tz+ctv7zJ0uWLIkpU6Zk7Y0ePTpeffXV2LJlS+bPqS9fvjxGjRqVdd1tt90Wy5Yta9N5AAAgn3xZm+Patm3b4vTTT4/6+vrM3j333BOVlZWHvH7z5s3xV3/1V7Fx48bM3rRp02L69OltPtuzzz4bX/jCFzLr4uLieP7556OiouKQ17/00ksxZsyYrL/998UXX4yLL774sGfcfvvt8S//8i8xefLk+PrXvx6nnHLKUec61N9E3F7/DAAA6Lq6+rv60dTV1cWwYcOirq4uIiK+//3vH/S3EPuyNgAAbc17+h81NDTEZz7zmVi1alVm7x//8R/j3nvvjeLi4qPev3fv3igoKMgKUQAAIJX39Iibb745fvCDH2TWvXv3jiVLlsTQoUMPe8+WLVvic5/7XGzatCmz9zd/8zfxzDPPHPXXBQAAR9OZ39P/9GXtj3/84zF8+PC48MILY/jw4TF8+PB46KGHss7M9cvaI0eOjCVLlmTWl19+eSxYsCBKSkoOurahoSGuuuqqqKqqyuxVVFTESy+9lHw+AAB0Jr6szXHtvvvuy/pNcEVFRUydOvWw1w8cODBmz56dtffAAw/Etm3b2ny2b33rW1nrysrKw/7PqoiIUaNGHTT7nXfeecQzxo0bF+vXr4/vfOc7LQq1IyL+9m//NiZPnpy1N2fOnBbdCwAALdXV39WP5pZbbsmE2hdccEF84xvfyOl5AADQEt7T/+iee+7JCrUnTZoUM2fObFGoHRHRvXt3oTYAAG3Ge3oc9LXCO+6444ihdkTEgAED4r777svaW7RoUezateuo5wEAwNF05vf0adOmRXV1dbz//vvxq1/9Ku688874whe+ECeffHKbnvPrX/86K9Tu06dPzJkz55ChdkRESUlJPProo9GnT5/M3ssvvxzPPfdcm84FAAD5ItbmuNXY2Bhz587N2vv2t78dBQUFR7zvkksuiYsuuiizrq+vj/nz57fpbG+99VYsW7Yssy4rK4tvfvObR71vypQpUVb2f+3dd5QU5NUw8LvL0lkW0EVEkaZSVCwYQbDgG0SjIsQWiBoLUVQ8kc+C+pooYowC9qhJFBuaqMGCDUNRihUVFV8BK02KAlIEls5+f3CcMLuUmWHZXeD3O2fPmfvMU+5MzDl32L3zVE/E7777bkyZMmWz84866qjYfffd087v2muvTXqfZs+eHZ9//nna+wAAwKao1bfs1VdfjaeffjoiIipUqBAPP/xwVKhQIaO9AAAgVer0DebNmxe33XZbIm7YsGEMHDgwg6wBAGDbqdMjVqxYkXQ7dkTEaaedllKOp556auTk5CTiNWvWxMyZM1NaCwAAm1Oe6/SIiMMOOywaNGhQ4vsWVbT5vFevXpGfn7/FNXXr1o3LLrtsi/sAAMCOSrM2O61333035s+fn4ibNGkSHTp0SGltjx49kuKhQ4eWYGbFv/H3rLPOitzc3K2uy83NjTPPPDNprKRzi4jYY489Yv/9908a88sqAABKilp983766ae49NJLE3Hv3r3j0EMPTXsfAABIlzp9gyeeeCJWrVqViK+55pqoVq1a6skCAEAJUqdHLFy4sNhYqo0n1apVK3bJweLFi1NaCwAAm1Oe6/TSsmrVqhg+fHjS2IUXXpjS2qLzXn/99Vi9enWJ5QYAAGVFszY7rddeey0pPv7447f6jWUbz93YmDFjYvny5dstt06dOqW8tmhur776aonkVFTt2rWT4iVLlmyXcwAA2PWo1TevT58+MWvWrIiIaNSoUfTr1y/tPQAAIBPq9A0eeeSRxOOcnJz4zW9+k/JZAABQ0tTpEXl5ecXGVqxYkfJZRecWbd4GAIB0lec6vbQUzbtZs2bRsGHDlNY2atQo9ttvv0S8dOnSGDt2bInnCAAApU2zNjutTz/9NClu165dymvr168fjRo1SsSrV6+OyZMnl0hehYWF8dlnn2WcW/v27ZPiiRMnRmFhYYnktrHZs2cnxbvttluJnwEAwK5Jrb5pY8eOjYceeigR/+1vf3ODHwAApUadHvHtt9/Gl19+mYgPOuggjRwAAJQpdXpEjRo1omnTpkljH374YUrnfPXVV0mXE9SuXTv23XfflPMEAIBNKa91emnalvcgovhngqL7AQDAjkizNjutKVOmJMUtW7ZMa33R+UX3y9SMGTOioKAgEVevXj322WeflNc3bNgwqWFj+fLl8d1335VIbj+bNm1a4ja/n238DWYAALAt1OrFrVixIi666KLEH6N17949TjzxxJTPBgCAbaVOL97wcfDBBycez549O/7yl79E27ZtY88994wqVarEXnvtFW3bto3//d//jY8//jjlnAAAIFXq9A1+85vfJMV33HFHSufcfvvtSfEFF1wQ2dn+XA4AgG1TXuv00uQ9AACA4vzrMzulFStWxMyZM5PGGjRokNYeRedvfJvGtii6T7p5bWpNSeX2s8cffzzpG4tbtGgRjRs3LtEzAADYNanVN+2mm26Kr7/+OiIi6tSpE/fcc0/aZwMAQKbU6RsUbdZu0qRJFBYWxr333htNmzaNG264IcaPHx/ff/99rFq1KubMmRPjx4+P2267LVq3bh1nnnlmfP/992nnBwAAm6JO/6+rrroq6tWrl4iHDx8evXr1itWrV29y/vr166Nv377x2GOPJZ33pz/9Ke08AQBgY+W5Ti9N2/qZYGd4DwAAoCjN2uyUFixYkNRsXLFixahbt25ae+y1115J8bx580okt6L77L333mnvsb1yi4iYO3duscaQ888/v8T2BwBg16ZWL27ChAlx1113JeKBAwem/Z4AAMC2UKdv8M033yTFNWvWjJ49e0bv3r1j1apVWz3nueeei7Zt28YXX3yRdo4AAFCUOv2/6tSpE0OHDo28vLzE2IMPPhj77rtvXHfddfHss8/Gf/7zn3juuefixhtvjObNm8fNN9+cmNuoUaMYOXJk1KpVK+08AQBgY+W5Ti9N2/qZYGd4DwAAoKicsk4Atodly5YlxdWqVYusrKy09qhevfoW98xU0X2KnpOK7ZVbYWFh/P73v4+ffvopMbbXXntFr169SmR/AABQqydbs2ZN9OjRI9atWxcRER06dIgLL7ww7XMBAGBbqNM3WLx4cVI8ePDg+PjjjxPxYYcdFt26dYv99tsvIiK++uqreOaZZ+KTTz5JzJkxY0acdNJJ8emnn0bNmjXTzhUAAH6mTk/Wpk2b+OSTT+Lyyy+PYcOGRUTEd999F/3799/smlq1asXFF18cN9xwg/ocAIASUZ7r9NK0rZ8Jdob3AAAAinKzNjuloh/YqlSpkvYeVatW3eKemSrPud1+++2JX2j97MEHH8zol2oAALAp5bkeLovc+vfvHxMnToyIiMqVK8c//vGPtM8EAIBtpU7foGiz9s+N2tnZ2XH//ffHRx99FNdcc0107do1unbtGn369IkJEybEXXfdlfTHeNOmTYvevXunnScAAGxMnV5c48aN47XXXotHH300ateuvcW51apVi169esVll12mURsAgBJTnuv00rSt78PO8B4AAEBRmrXZKa1cuTIprlSpUtp7VK5cOSlesWLFNuX0s/Ka20svvRR//OMfk8YuueSSOPXUU7d5bwAA+Fl5rYcjSj+3KVOmxJ///OdE/Mc//jH233//tM8EAIBtpU7fYHN/DNa/f//o1avXJm9HycrKiv/3//5f9OvXL2n8ySefjJkzZ6adKwAA/EydXtzo0aPj0EMPjQsvvDAWLVq0xbkFBQVx6623xn777RdXXnllrFq1Ku0cAQCgqPJcp5embX0fdob3AAAAitKszU6p6LdzrV69Ou09iv6SJpNvPtuU8pjb+++/H7/97W9j/fr1ibGjjz467rnnnm3aFwAAiiqP9fDm9tmeua1fvz569OiRmH/AAQfEtddem/Z5AABQEtTpmx9v0aJFXHnllVs947rrrot99903Ea9duzYeffTRNDMFAID/Uqcnu+OOO6Jjx47x6aefRkRExYoVo0ePHjFixIiYN29erF69On788ccYO3Zs9O7dO6pVqxYREWvWrIm77747OnXqFAUFBWnnCQAAGyvPdXpp2tb3YWd4DwAAoCjN2uyUatSokRQX/fauVBT9hq6ie2aqvOU2adKkOPnkk5N+IXXwwQfHK6+8UuxbywAAYFuVt3p4S/tsz9z++te/xnvvvRcRG27ie+ihh6JixYppnwcAACVBnb758R49ekR29tZ/nZaTkxMXXnhh0tjYsWPTyBIAAJKp0//rqaeeimuuuSZxCUF+fn689dZbMWjQoDj++OMjPz8/KlasGHXq1Iljjjkm7r777pgwYUI0adIksce4cePi0ksvTTtPAADYWHmu00vTtr4PO8N7AAAARWnWZqdU9ANbQUFBFBYWprXH8uXLt7hnporuU/ScVJRUbtOmTYtOnTrFwoULE2P77bdfDB8+PPLy8jLaEwAAtkStHjF9+vS44YYbEvEll1wS7dq1S/ssAAAoKer0zY8fe+yxKZ9TdO5HH32U8loAAChKnb7BkiVL4vLLL08a+/e//x1t2rTZ4v7NmzePV199NSpVqpQYGzx4cHzwwQdp5woAAD8rz3V6adrWzwQ7w3sAAABFadZmp7T77rtHVlZWIl6zZk3MmzcvrT1mz56dFNetW7dEciu6z6xZs9LeoyRymzNnTnTs2DHmzJmTGGvQoEGMGjUq9thjj7T3AwCAVKjVI/r27Zv4pVP9+vXj9ttvT/scAAAoSer0DTb1b+P7779/yuc0a9YsKV62bFmx20EAACBV6vQNnnjiiViyZEki7tSpU3To0CGlM1q0aBG/+93vksYefvjh9BIFAICNlOc6vTRt62eCneE9AACAojRrs1OqWrVq7LPPPkljM2fOTGuPovObN2++zXlFFP9jre+++y7tPYquSTe3BQsWRMeOHWPq1KmJsbp168aoUaOKvW8AAFCS1OoRixcvTjyeM2dO5OXlRVZW1lZ/imrcuHHS8/fcc0/a+QIAQIQ6/WctWrRIirOysiI3Nzflc2rWrFlsbNGiRSmvBwCAjanTN3jjjTeS4s6dO6d1TtH548aNS2s9AABsrDzX6aWp6GeCXfE9AACAojRrs9Mq+qFt8uTJaa2fMmXKFvfLVMOGDaNq1aqJePny5TFjxoyU18+YMSMKCgoScfXq1aNBgwYpr1+yZEmccMIJSa+vVq1aMWLEiLRuCAEAgEyp1QEAoPxRp0e0bNkyKS4sLIzVq1enfNbKlSuLjVWrVi3l9QAAUJQ6PWLatGlJcePGjdPKtej8ojf4AQBAusprnV6avAcAAFCcZm12WoccckhS/O6776a8du7cuTF9+vREXLFixWJ/pJWprKysaNWqVca5vfPOO0lxq1atNnnL3qYsX748Tj755Pj4448TYzVq1IjXX389Dj744JRzAACAbaFWBwCA8kedHnHYYYcVG/vhhx9SPmvevHlJcYUKFSIvLy/l9QAAUJQ6PWLVqlVJcU5OTsrnRGx43Rtbt25dWusBAKCo8lqnl6ZteQ8iin8mKLofAADsiDRrs9M65ZRTkuJRo0ZFYWFhSmtHjBiRFB933HFRo0aN7ZbbyJEjU15bdG7nzp1TWrdq1aro2rVr0ofbKlWqxEsvvRRt27ZN+XwAANhWu3qt3q9fvxg5cmTaP0U99dRTSc+ffvrpKecKAABF7ep1esSGG/cOPPDApLEJEyakfFbRufvvv78vcAIAYJuo0yN22223pHjOnDkpnxNR/Cbt/Pz8tNYDAEBR5blOLy0dOnSI6tWrJ+KvvvoqZsyYkdLa6dOnx9dff52Ic3Nzo0OHDiWdIgAAlDrN2uy02rVrF7vvvnsinjp1aowZMyaltY888khS3KVLl5JMLU499dSkeMiQIbFs2bKtrlu6dGkMGTIk7dzWrl0bZ511VowaNSoxVrFixRgyZEj8z//8T4pZAwBAydjVa/VWrVpFx44d0/4pqn379knPN2jQII1XCgAAyXb1Ov1nv/71r5Pi559/PsUso9hZ/rgMAIBtpU6PaNSoUVL85ptvpp5kRLzxxhtJcdOmTdNaDwAARZXnOr20VKlSJTp16pQ09uijj6a0tui8E088MSpVqlRiuQEAQFnRrM1OKzs7O84///yksZtvvnmr31z2xhtvxFtvvZWIc3Nz46yzzirR3Fq1ahW/+MUvEvGyZctiwIABW103YMCAWL58eSJu27ZttGzZcotr1q9fH+eff368/PLLibHs7Ox46qmnin2zGwAAlAa1OgAAlD/q9A0uuOCCqFixYiIeMmRIfPHFF1s967PPPouhQ4cmjZX0+wAAwK5HnR7xy1/+MikeMmRIyjf2LVy4MP7xj39scT8AAEhXea7TS1OPHj2S4gceeCDmz5+/xTXz5s2LBx98cIv7AADAjkqzNju1a6+9NmrUqJGIx44dG/3799/s/NmzZ8fvf//7pLErrrgi6dvPNiUrKyvpJ5VvR+vXr19SfPvtt8e4ceM2O39Tuf/5z3/e6jm9evWKf/7zn0m5Dho0aIf+cA8AwI5PrQ4AAOWPOj2icePGcfHFFyfi1atXR7du3WLhwoWbXTN//vzo3r17rF27NjHWtm1bN2sDAFAidvU6vUuXLkmvf9WqVXHGGWfEokWLtrhu2bJlceaZZybV8hUrVozu3btvcR0AAKSiPNfppeXkk0+Otm3bJuIff/wxevToEWvWrNnk/NWrV0ePHj3ixx9/TIwdffTRccIJJ2z3XAEAoDRo1mantvvuu8f//u//Jo1df/31cdlll8WcOXMSY+vXr4+hQ4dGu3btYvr06Ynx+vXrx1VXXbVdcjvxxBOjU6dOiXjNmjVxwgknxL333hsFBQWJ8eXLl8c999wTJ554YtKH15NOOmmr3/Z78803x9///veksdNPPz0aNGgQo0aNSutn6tSpJfTKAQBArQ4AAOWROn2DG2+8MfLz8xPxxIkTo02bNvHyyy8nNWSvWbMmhg4dGm3atInJkycnxqtUqVLs3+YBACBTu3qdvvvuu8c111yTNPbRRx/FoYceGoMHD45ly5YlPbdixYoYMmRIHH744fHmm28mPXfxxRdH06ZN036dAABQVHmu01euXJny34PPnTt3s3Pnzp271bMGDhwY2dn/bUl55ZVXolOnTvHxxx8nzZswYUJ06tQpXn311cRYhQoVYsCAAdv4agEAoPzIKiwsLCzrJGB7Wr9+fXTp0iXpw13Ehg94DRs2jLy8vJg2bVosXrw46fmqVavGyJEjo3379ls9IysrKykePXp0Sjdm/PDDD3HkkUfGtGnTip3dpEmTKCwsjKlTp8bKlSuTnm/atGm89957SX8stikdOnSIsWPHbjWPVNx0003Rt2/fEtkLAAAidu1aPRNFX8u0adOiUaNGJX4OAAC7NnX6BmPGjIlf/epXxfbKy8tL1OHTpk2Ln376Ken5ChUqxGOPPRbnnntuymcBAMDW7Op1+rp166Jr167FXn9ERE5OTuy7776Rl5cXS5cujW+//TZWrVpVbF779u1j1KhRUaVKla2eBwAAqSivdfr06dOjcePGKb2GLXnsscfi/PPP3+q8AQMGxLXXXltsvH79+rHnnnvGnDlzNtn4feedd8aVV165zXkCAEB54WZtdnrZ2dkxZMiQ6NatW9L4unXrYurUqfHJJ58U+xC82267xbBhw1L6ELwt9thjjxg9enQcfPDBSeMrVqyISZMmxeTJk4v9suqQQw6J0aNHb5fmDwAAKE1qdQAAKH/U6Rt06NAhhg8fHnXr1k0aX7JkSUycODEmTpxYrFG7Zs2aMXToUI3aAACUuF29Tq9QoUIMGTIkLrvssmLPrV27Nr744osYP358TJ48eZON2meffXYMGzZMozYAACWqPNfppalPnz5xxx13RIUKFZLG58yZExMmTCjWqF2hQoW4++67NWoDALDT0azNLqFKlSrx9NNPx3PPPReHHHLIZudVr149Lrvsspg8eXJK3w5cEho2bBgffPBB9O/fP+rXr7/ZefXr148BAwbE+PHjo0GDBqWSGwAAbG9qdQAAKH/U6Rscc8wxMWXKlLj66qujVq1am51Xp06d6N27d3zzzTdxyimnZHQWAABsza5ep1epUiUeeOCBeO+996J79+5RtWrVLc6vVKlSdOnSJd5444146qmnombNmmmdBwAAqSjPdXppuuqqq+Kjjz6Kk08+ObKzN92ikp2dHaecckpMmDAhevfuXboJAgBAKcgqLCwsLOskoLR98803MX78+Jg9e3asXr06atWqFS1atIj27duX6bforl+/PiZMmBATJ06MefPmRURE3bp145BDDonDDjtssx9eAQBgZ6FWBwCA8kedHrFmzZr44IMPYtKkSbFgwYKoWLFi5OfnR/PmzeOII47wmQAAgFK3q9fpa9asiYkTJ8bkyZNj0aJFsWzZsqhWrVrUrl079t9//2jdunVUrly5RM4CAIBUldc6vTQtWLAg3n777Zg6dWosX748qlevHk2bNo327dvH7rvvXtbpAQDAdqNZGwAAAAAAAAAAAAAAAAAAIAO+5h8AAAAAAAAAAAAAAAAAACADmrUBAAAAAAAAAAAAAAAAAAAyoFkbAAAAAAAAAAAAAAAAAAAgA5q1AQAAAAAAAAAAAAAAAAAAMqBZGwAAAAAAAAAAAAAAAAAAIAOatQEAAAAAAAAAAAAAAAAAADKgWRsAAAAAAAAAAAAAAAAAACADmrUBAAAAAAAAAAAAAAAAAAAyoFkbAAAAAAAAAAAAAAAAAAAgA5q1AQAAAAAAAAAAAAAAAAAAMqBZGwAAAAAAAAAAAAAAAAAAIAOatQEAAAAAAAAAAAAAAAAAADKgWRsAAAAAAAAAAAAAAAAAACADmrUBAAAAAAAAAAAAAAAAAAAyoFkbAAAAAAAAAAAAAAAAAAAgA5q1AQAAAAAAAAAAAAAAAAAAMqBZGwAAAAAAAAAAAAAAAAAAIAOatQEAAAAAAAAAAAAAAAAAADKgWRsAAAAAAAAAAAAAAAAAACADmrUBAAAAAAAAAAAAAAAAAAAyoFkbAAAAAAAAAAAAAAAAAAAgA5q1AQAAAAAAAAAAAAAAAAAAMqBZGwAAAAAAAAAAAAAAAAAAIAOatQEAAAAAAAAAAAAAAAAAADKgWRsAAAAAAAAAoJybPn16ZGVlbfGnb9++ZZJbhw4dtphXo0aNyiQvAAAAAAAAKA05ZZ0AAAAAAAAAAKVn8eLF8X//93/x1VdfxaJFi2LNmjVRu3btqFevXrRp0yb23HPPsk4RAAAAAAAAAHYYmrUBAAAAAAAAykCjRo1ixowZJbLXiy++GF27dt3kc+vXr48xY8bEK6+8EqNGjYrPP/98i3u1bNkyevXqFeeff35Uq1Yt5RymT58ejRs3TiftLVq0aFHUqlWrxPbr27dv3HzzzYn4vPPOi8cff7zE9gcAAAAAAABg16RZGwAAAAAAAGAnNXz48Ljgggti7ty5Ka+ZPHly9OrVK+6555745z//Gb/4xS+2Y4akIysrK/H42GOPjTFjxpRdMpS5Tp06xTXXXJM01qRJkzLJ5c4774xFixYljZ1zzjnxww8/lEk+AAAAAAAAUJo0awMAAAAAAADspL7++uvNNmrXqVMn6tWrF9WrV48ffvghZs6cWWztscceG//5z3/imGOOKY10gTTsueee0bFjx7JOIyIiWrduXWysSpUqZZAJAAAAAAAAlD7N2gAAAAAAAADlwB133BEHH3xwRmtTWZeVlRUdO3aMbt26RYcOHYrdwDtz5sy477774p577ol169ZFRMSKFSuic+fOMWXKlKhfv37aeY0cOTLtNT+rUaNGxmsBAAAAAAAAoLRo1gYAAAAAAAAoB1q3bh0dOnQo8X0rVaoUPXv2jCuvvDIaNWq02Xn77LNP3HHHHfGrX/0qTj755Fi1alVERPz0009x/fXXxxNPPJH22eXl1l8AAAAAAAAA2F6yyzoBAAAAAAAAALaPdu3axVdffRX33XffFhu1N/bLX/4yBgwYkDT27LPPxrJly7ZDhgAAAAAAAACwY9OsDQAAAAAAALCTOuyww6Jhw4Zpr7v00ksjLy8vEa9atSrGjBlTgpkBAAAAAAAAwM4hp6wTAAAAAAAAAKB8qVixYrRt2zaGDx+eGJs5c2YZZrRjWblyZUyePDmmTJkS8+fPj+XLl0dubm7stttucdBBB8WBBx4Y2dnl57vVCwoK4p133onZs2fHvHnzokKFClG3bt1o2bJlHHbYYZGVlVWi53355Zcxfvz4mDNnTuKsI444Ilq0aFEi+69evTrGjx8fM2bMiPnz50dBQUHk5uZGw4YN48ADD4ymTZuWyDk7g6+++iomTpwYc+fOjaVLl0ZOTk5Ur1499tprr2jatGm0bNkycnL8aQkAAAAAAABsid+oAQAAAAAAAFBM7dq1k+IlS5aUUSY7hlmzZsUzzzwTr732Wrz33nuxatWqzc6tXbt2XHDBBXHVVVdF/fr1t7hvhw4dYuzYscXGx44du8Um6ptuuin69u27xb3feeeduPXWW+PNN9/cbL5169aNnj17xjXXXBO5ublb3C8iYvr06dG4ceNEfN5558Xjjz8eEREjRoyIG264IT766KNNrm3RokX0798/OnfuvNVzNuW9996L2267Ld54440oKCjY7LxGjRrFGWecEZdccklS4/b7778fRx55ZCI+/vjjY8SIEWnncd9998UVV1yRiPv06RP9+/dPe5/tZdWqVXHPPffEww8/HN9+++0W51atWjWOPPLIOPPMM+OSSy4ppQwBAAAAAABgx1J+vqobAAAAAAAAgHJj9uzZSfFuu+1WRpmUf5999lnss88+cc0118SYMWO22KgdEbFo0aK46667omXLlvH666+XUpb/tXz58jjrrLPiqKOOitdff32L+c6bNy9uueWW2H///ePDDz/M+Mw+ffrECSecsNlG7YiIKVOmxKmnnhq33HJLWnsvXbo0zjjjjGjXrl288sorW2zUjtjQUH7HHXdEjx49ksbbtm0brVq1SsSjRo2K6dOnp5VLRMTDDz+ceJyVlRUXXXRR2ntsLzNnzoxDDjkkrrvuuq02akdErFixIt5888249NJLY+3ataWQIQAAAAAAAOx4NGsDAAAAAAAAkGT58uXx8ccfJ43tv//+ZZRN+bd69eooLCxMGqtUqVI0bdo0Dj300DjiiCNiv/32i5ycnKQ5S5YsiVNOOSVGjx5darnOmzcvjj322BgyZEix5/bee+9o3bp1HHLIIcVuVv/++++jQ4cO8fbbb6d95nXXXRcDBw5MxLm5uXHAAQfE4YcfHvn5+cXm33jjjfHCCy+ktPesWbPiyCOPjOeff77Yc7m5udG8efM44ogjolmzZlGlSpWt7rfx7dGFhYXxyCOPpJTHz95///34/PPPE3GHDh1i3333TWuP7WXFihXRsWPH+OKLL5LGs7Ozo2HDhtG6des44ogjonnz5lGjRo0yyhIAAAAAAAB2PDlbnwIAAAAAAADAruTf//53LF++PBHXrFkz2rdvX4YZ7RiOPfbY6Nq1axx//PHRrFmzYs3ZK1eujOHDh8df/vKX+OCDDyIiYv369XHOOefEl19+uckG2TvvvDMWLVoUERHHH398YrxVq1Zx5513bjaXJk2aFBtbv359dOvWLSZMmJAYy8/Pjz59+sQ555wT9erVS5r73nvvxY033hhvvvlmREQUFBRE9+7d49NPP035pvVx48bFtGnTIiKiTZs2ccstt8Rxxx2XeG8KCwtj7NixcemllyY1Ef/hD3+IU089tdh7uLHVq1fH6aefHpMmTUoa79q1a1x11VVx5JFHRoUKFRLja9eujU8//TSGDh0aTz755Cb3PPvss6NPnz6xbNmyiIh47LHHom/fvkn7bMnGt2pHRLm6Vfv++++Pr7/+OhHn5+fHrbfeGmeccUax5vzCwsKYOnVqjBo1Kl544YUYOXJkaacLAAAAAAAAOwzN2gAAAAAAAADlwIQJE2Lt2rVpr6tbt260atWqxPIoKCiIfv36JY2dffbZUbFixbT3GjVqVEY5NGvWLBo0aJDR2rKwzz77xOeffx4HHHDAFudVqVIlunTpEp07d46ePXvGoEGDIiJizpw58eSTT8all15abE3r1q03uVft2rWjY8eOaeU5cODApFu827RpEy+//HLUrVu32Nzs7Oxo3759jBw5Mq644oq4//77I2LDTdb9+vWLe++9N6Uzf27UPv/882PQoEHFmp6zsrKiQ4cOMW7cuDjkkENizpw5ERExe/bseO2116JLly6b3fumm25KNL1HbLjN/PHHH4/u3btvcn5OTk4cfvjhcfjhh8dNN90U77//frE5NWvWjO7duyearmfPnh3Dhg2Lzp07b/W1Ll26NJ599tlEvNtuu8Vpp5221XWlZePb1CtXrhzjxo2L5s2bb3JuVlZWNG3aNJo2bRo9e/aML774IuWGdQAAAAAAANjVaNYGAAAAAAAAKAeuvvrqjNZ16dIlhg4dWqJ5TJ8+PRFXr149/vjHP2a018Y3Qafj7rvvjt69e2e0tizUrVt3kw3Pm5OdnR0PPPBAjB49Or799tuI2HCD86aatUtKQUFBDBgwIBHvueeeMWzYsKhTp85Wc73nnnvio48+SjQ3P/roo3HzzTdHrVq1Ujr78MMPj4ceemiLzb75+fnxpz/9Kek9eP311zfbrL1w4cL461//mjR2//33b7ZRu6iKFSvG0UcfvcnnevbsmXRD9sMPP5xSs/bTTz+ddCP9ueeeG5UrV04pn9Lw1VdfJR4fd9xxm23U3pR05gIAAAAAAMCuJrusEwAAAAAAAACgfHj66afjb3/7W9LYbbfdFvXr1y+jjHZelSpVijPPPDMRf/LJJ7FixYrtdt7gwYNj4cKFibhv375bbdT+WYUKFeL6669PxMuWLYvhw4enfHa/fv1Supn9rLPOSoo//vjjzc4dNGhQUmP00UcfHRdddFHKOW1J69at4/DDD0/Ew4YNi9mzZ2913cYN3hFRYvmUlI3/+0rlfw8AAAAAAAAgNZq1AQAAAAAAAIgPPvggevTokTR20kknxeWXX15GGe38GjdunHi8du3a+Pzzz7fbWcOGDUs8zsnJiW7duqW1/pe//GVkZ//3TwzeeuutlNbl5eXFCSeckNLcOnXqxD777JOIv/vuu83OHTFiRFL8hz/8IaUzUtWzZ8/E43Xr1sVjjz22xfkTJ06Mjz76KBG3a9cuWrZsWaI5bauNv3Rh3LhxMXPmzDLMBgAAAAAAAHYemrUBAAAAAAAAyoHRo0dHYWFh2j9Dhw7d5rO/+eab6Ny5c9LNu82bN48nn3wysrKyMt43k9dTWFgYvXv33ubXVFYKCgrimWeeiZ49e0bbtm2jfv36kZubG9nZ2ZGVlZX0s3FDcETEggULtktOhYWF8c477yTi/fffP2rWrJnWHtWrV4/ddtstEU+ZMiWldYcddlhSk/fW1K1bN/F4yZIlm5yzdu3aeP/99xNxdnZ2nHjiiSmfkYru3bsnvUePPPJIFBYWbnZ+eb9VOyLi+OOPTzxesmRJHHfccTFkyJBYs2ZNGWYFAAAAAAAAOz7N2gAAAAAAAAC7sDlz5kSnTp1i3rx5ibEGDRrEiBEjok6dOmWY2Y5lzZo10b9//6hXr1507949HnrooRg/fnzMnTs3li1btsVG358tXrx4u+T2ww8/xMKFCxPx5MmTizWOp/Izf/78xB4b77clGzdfp6J69eqJxxt/ecDGvv/++1i+fHkibtasWdSoUSOtc1LJ49xzz03E06dPj5EjR25y7ooVK+Kf//xnIq5Zs2acddZZJZpPSbjmmmuiWrVqiXjq1Klx1llnRd26daNbt27x97//PT777LNYv359GWYJAAAAAAAAOx7N2gAAAAAAAAC7qIULF0anTp1i2rRpibH8/PwYOXJkNGjQoAwz27GsWLEiTjzxxLjuuuti6dKlGe+zatWqEszqv3788ccS33Nzt14XVaVKlRI/u2ijeLoN4akqevP5oEGDNjnvueeeS2q0P/vss5OaosuL/fbbL5577rlit6ovXrw4nn322bj00kvj4IMPjt133z1OP/30ePrppzfbMA8AAAAAAAD8V05ZJwAAAAAAAABA6Vu6dGmceOKJMWnSpMRYXl5eDB8+PJo1a1aGme14LrvssnjzzTeTxvLz86NDhw5x8MEHR4MGDaJmzZpRtWrVqFChQmLOiBEjYuDAgds9v+1xY3dZ3r5ctCG+pG/V/tlBBx0U7dq1i3fffTciIl566aWYP39+5OfnJ817+OGHk+KLLrpou+RTEn71q1/FpEmT4pZbbol//etfsWzZsmJzFi1aFC+88EK88MILkZ+fH3/605/i8ssvj6ysrDLIGAAAAAAAAMo/zdoAAAAAAAAAu5gVK1bEKaecEh9++GFirFq1avHaa6/FoYceWoaZ7Xg+/fTTeOKJJxJxxYoVY8CAAXHZZZdFpUqVtrj222+/3d7pRUQUu+W5ZcuWce+9927TnlWrVt2m9dsiNzc3Kd5Uw3FJ6dmzZ6JZe/Xq1fHEE0/E1VdfnXj+yy+/jLfeeisRt27dutz/f2jvvfeOf/zjH3HXXXfFqFGjYsyYMTFu3LiYOHFirFu3Lmnu/Pnz4w9/+EOMHTs2nn322aQvGwAAAAAAAAA20KwNAAAAAAAAsAtZvXp1nH766TFu3LjEWOXKlWPo0KHRvn37Msxsx/Tvf/87CgsLE/HNN98cvXv3TmntwoULt1NWyXbfffekuLCwMDp27FgqZ28PderUSYrnzZu33c4666yzonfv3rFo0aKIiBg0aFBSs/agQYOS5pfnW7WLql69enTp0iW6dOkSERE//fRTvP322/Haa6/F008/nXjNERHPP/983HnnndGnT5+yShcAAAAAAADKreyyTgAAAAAAAACA0rFu3br47W9/G6+//npiLCcnJ5555pk4/vjjyzCzHdf777+feJydnR2XXHJJymsnTZq0PVIqpl69ekk3Yc+YMSPWrFlTKmdvD/Xq1YsaNWok4i+//HK73a5dpUqVOO+885LO+vmLDn6+aftn1atXj9/+9rfbJY/SULNmzTjppJPigQceiO+++y4uuOCCpOfvvvvupC8mAAAAAAAAADbQrA0AAAAAAACwCygsLIwLL7wwnn/++cRYdnZ2PPbYY9G1a9eyS2wH98MPPyQe5+fnR+3atVNat379+hg7dmxaZ2VlZSUep9M0W7FixaRb0wsKCmL8+PFpnV2e5OTkxJFHHpmI169fH//5z3+223k9e/ZMih9++OGIiHjppZdi/vz5ifFu3bpFbm7udsujNFWvXj0eeuihaNSoUWLs+++/j2+++abskgIAAAAAAIBySrM2AAAAAAAAwC7g8ssvj8GDByeNPfjgg3HOOeeUUUY7h42bplevXp3yupdffjlmzZqV1lnVq1dPPC4oKEhr7YknnpgU//Wvf01rfXlT9PXcd9992+2s5s2bx7HHHpuIn3vuuVi0aFEMGjQoad5FF1203XIoCzk5OdGmTZuksQULFpRRNgAAAAAAAFB+adYGAAAAAAAA2Mldf/318eCDDyaN3XHHHcVuDCZ99erVSzxetGhRTJ48eatrli1bFldddVXaZ9WpUyfxePr06Wmt/f3vfx+1atVKxM8991y89tpraedQXlx44YVJt1i/9dZbiRuvt4dLLrkk8XjlypXx5z//OUaOHJkYO+igg4o1Nu8MijZnp3pzPAAAAAAAAOxKNGsDAAAAAAAA7MT69+8ft99+e9LYTTfdlFGzMMW1a9cuKe7Tp0+sX79+s/MLCgritNNOi6lTp6Z91gEHHJB4vGDBghgzZkzKa/Py8uLaa69NxOvXr4/u3bvHyy+/nFYOEyZMiN/85jdprdkeatWqFVdccUXS2OWXXx7PPPNMSuvXrFkTb731VsrnnXbaaZGfn5+I77rrrqRb1cv7rdpTpkyJSy+9NL755puU13z44YdJ/43VqlUrmjRpsh2yAwAAAAAAgB1bTlknAAAAAAAAAMCGJti1a9dmtLZu3brRqlWrYuNPPPFEXHfddUljRx11VBx11FExatSotM6oX79+tGzZMq016Z6xsWbNmkWDBg0yXr81c+fOzTi/Aw44IPbcc8+IiDjnnHPitttuSzRov/baa9G5c+cYOHBg0vu1cuXKePXVV+P6669PNMy2aNEipkyZkvK5nTp1itdffz0R//rXv46ePXtG69atIy8vL7Kz//t97U2aNCnWWNunT5946623YtiwYRERsXTp0ujatWt07do1Lr/88mjfvn1Urlw5ac3KlSvjs88+i1GjRsXzzz8fH3/8cUREPPvssynnvb3ceOONMWrUqHj//fcjImL16tXRvXv3GDJkSFx55ZXRtm3bqFChQmL+2rVrY+LEifHiiy/G4MGDo0mTJik3vFeqVCkuuOCCGDBgQLHnqlSpEuecc06JvKbtZdWqVfH3v/89HnrooTjqqKPijDPOiOOOOy5atGiR9B5FRMyfPz+efPLJ6Nu3b6xbty4xft5550WlSpVKO3UAAAAAAAAo9zRrAwAAAAAAAJQDV199dcZru3TpEkOHDi02Pnr06GJjb7/9dhx//PFpn3HeeefF448/ntaaTM752d133x29e/fOeP3WjBgxIkaMGJHR2sceeyzOP//8iIho3rx5XHLJJfHggw8mnh82bFgMGzYsGjRoEHvuuWcsW7Yspk+fHgUFBYk5xxxzTJx77rlp3cj8u9/9Lm699dZYsGBBREQsXrw4+vfvv8m5N910U/Tt2zdpLDs7O/71r39F165dE03KhYWF8eKLL8aLL74YlStXjoYNG0bt2rVj5cqVsXjx4pg1a1ZSw255UrFixXjuuefihBNOiEmTJiXGX3jhhXjhhRciNzc3GjRoELm5ubFkyZKYPn16rFy5MjEv3VuiL7744hg4cGDSjdoREWeccUbUrl17215MKVm/fn2MGzcuxo0bFxERVatWjb322iuR/7x582LmzJnFXuN+++0Xt9xyS6nnCwAAAAAAADuC7K1PAQAAAAAAAAA25+67745TTjml2Ph3330XH3zwQUyePDmpUfu4446Ll156KXJy0vt+9Tp16sTzzz8fdevWzTjXvLy8GDlyZFx55ZXFzl+1alV89dVXMX78+Jg4cWLMmDFjk43a2/PG83Tttdde8c4778Spp55a7LmlS5fG5MmTY/z48fHFF18kNWpnomnTptGxY8di4+k03Jc3K1asiG+++SY+/PDD+PDDD2PGjBnFGrWPPPLIeOuttyI3N7eMsgQAAAAAAIDyTbM2AAAAAAAAAGyDSpUqxUsvvRR333131KtXb7PzGjVqFPfff3+MGjUqatWqldFZxxxzTHzxxRdx//33R+fOnaNx48aRm5sb2dmp//o/Jycn7rzzzvjyyy/j4osvTqn5u1GjRnHxxRfHiBEjYvr06Rnlvr3k5eXFSy+9FKNHj45OnTpFpUqVtji/WbNm8cc//jEGDx6c9lkXXnhhsb2OOeaYtPcpba1atYp33nknrr322mjdunVKXxTQrl27GDx4cLzzzjuxxx57lEKWAAAAAAAAsGPKKiz6lcgAAAAAAAAAQEbWrl0bH374YXz22Wfx448/RoUKFaJevXpxyCGHxMEHH1zW6W1SYWFhTJo0KSZNmhQLFiyIxYsXR+XKlSMvLy8aN24cLVu2jPr165d1milbvnx5vPPOOzFr1qxYsGBBrFu3LmrWrBmNGzeOVq1axd57753x3jfeeGPccsstiXjgwIFx9dVXl0TaWzV9+vRo3LhxIj7vvPPi8ccfz2iv5cuXx6RJk+Lbb7+NH374IZYvXx45OTmRl5cXTZo0iUMPPTTy8/O3Kd9GjRrFjBkzIiKiYcOG5a7JHwAAAAAAAEqKZm0AAAAAAAAAgK1Yt25dNGrUKGbNmhURG25UnzVr1jY3NaeqJJu1S4NmbQAAAAAAAHYV2WWdAAAAAAAAAABAeTds2LBEo3ZExK9//etSa9TelCeeeCKysrKSfvr27VsmuXTo0KFYLj83agMAAAAAAMDOTrM2AAAAAAAAAMBWDBgwICnu1atXGWUCAAAAAAAAlCeatQEAAAAAAAAAtuDxxx+Pt99+OxEffvjhcfTRR5dhRgAAAAAAAEB5kVPWCQAAAAAAAAAAlBdz586NSZMmRUTEvHnzYtSoUTF48OCkOf369Sv1vOrVqxcjR47c4pwmTZqUUjbJ7rzzzli0aNFmn69atWopZgMAAAAAAAClK6uwsLCwrJMAAAAAAAAAACgPHn/88bjgggs2+/wZZ5wRQ4YMKcWMAAAAAAAAgPIsu6wTAAAAAAAAAADYEbRp0yYeeeSRsk4DAAAAAAAAKEdyyjoBAAAAAAAAAIDyKCsrK2rWrBkHHnhgdOvWLXr27BkVK1Ys67QAAAAAAACAciSrsLCwsKyTAAAAAAAAAAAAAAAAAAAA2NFkl3UCAAAAAAAAAAAAAAAAAAAAOyLN2gAAAAAAAAAAAAAAAAAAABnQrA0AAAAAAAAAAAAAAAAAAJABzdoAAAAAAAAAAAAAAAAAAAAZ0KwNAAAAAAAAAAAAAAAAAACQAc3aAAAAAAAAAAAAAAAAAAAAGdCsDQAAAAAAAAAAAAAAAAAAkAHN2gAAAAAAAAAAAAAAAAAAABnQrA0AAAAAAAAAAAAAAAAAAJABzdoAAAAAAAAAAAAAAAAAAAAZ0KwNAAAAAAAAAAAAAAAAAACQAc3aAAAAAAAAAAAAAAAAAAAAGdCsDQAAAAAAAAAAAAAAAAAAkAHN2gAAAAAAAAAAAAAAAAAAABnQrA0AAAAAAAAAAAAAAAAAAJABzdoAAAAAAAAAAAAAAAAAAAAZ0KwNAAAAAAAAAAAAAAAAAACQAc3aAAAAAAAAAAAAAAAAAAAAGdCsDQAAAAAAAAAAAAAAAAAAkAHN2gAAAAAAAAAAAAAAAAAAABnQrA0AAAAAAAAAAAAAAAAAAJABzdoAAAAAAAAAAAAAAAAAAAAZ0KwNAAAAAAAAAAAAAAAAAACQAc3aAAAAAAAAAAAAAAAAAAAAGdCsDQAAAAAAAAAAAAAAAAAAkAHN2gAAAAAAAAAAAAAAAAAAABnQrA0AAAAAAAAAAAAAAAAAAJABzdoAAAAAAAAAAAAAAAAAAAAZ+P9do4LftlkIOAAAAABJRU5ErkJggg==", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ + "from message_tree.message_tree_algorithms import e2e_latency_breakdown\n", + "\n", "##################################################\n", "# Filter DFG paths through must-be-included and\n", "# cannot-be-included patterns\n", @@ -555,20 +166348,93 @@ " if all(re.search(f.removeprefix(\"^\").removesuffix(\"$\"), k) for f in E2E_INCL_PATH_PATTERNS)}\n", "\n", "\n", - "print(len(cohorts), len(cohorts_filt))\n", - "for k, v in cohorts_filt.items():\n", - " print(f\"\\n\\n ({len(v)})\\n \", end=\"\")\n", - " print(\"\\n -> \".join(k.split(\" -> \")))\n", + "#print(\"cohorts:\", len(cohorts), \", cohorts_filt:\", len(cohorts_filt))\n", + "#for k, v in cohorts_filt.items():\n", + "# print(f\"\\n\\n ({len(v)})\\n \", end=\"\")\n", + "# print(\"\\n -> \".join(k.split(\" -> \")))\n", "\n", - "if len(cohorts_filt) != 1:\n", - " print(f\"[WARN] Expected exactly one cohort to remain, got {len(cohorts_filt)}. Only the first one will be used.\")\n", + "for relevant_path, relevant_dataflows in iter(cohorts_filt.items()):\n", + " topics = [topic for topic in relevant_path.split(\" -> \") if topic.startswith(\"/\") and not topic.startswith(\"/void\")]\n", + " name = f\"{topics[0]}-{topics[-1]}\"\n", + " name = name.replace(\"/\", \"_\").replace(\" \", \"_\").replace(\":\", \"_\")\n", "\n", - "relevant_path, relevant_dataflows = next(iter(cohorts_filt.items()))" + " ##################################################\n", + " # Break down the E2E latency into its constituent\n", + " # latencies.\n", + " ##################################################\n", + " e2e_breakdowns = list(map(e2e_latency_breakdown, relevant_dataflows))\n", + "\n", + " ##################################################\n", + " # Output the chosen DFG path to a file\n", + " ##################################################\n", + " conv_items = [i for p in e2e_breakdowns for i in p]\n", + " with open(os.path.join(OUT_PATH, f\"plot_e2es_path_{name}.txt\"), \"w\") as f:\n", + " f.write(f\"Number of path instances: {len(relevant_dataflows)}\\n\")\n", + " f.write( \" \" + \"\\n -> \".join(relevant_path.split(\" -> \")))\n", + " f.write(\"\\n\")\n", + "\n", + " conv_items_unique = set(conv_items)\n", + "\n", + " def e2e_breakdown_type_hist__(items):\n", + " \"\"\"\n", + " Given a list of e2e breakdown instances of the form `(\"\", )`, plots a histogram for each encountered\n", + " type.\n", + " \"\"\"\n", + " plot_types = (\"dds\", \"idle\", \"cpu\")\n", + " #assert all(item.type in plot_types for item in items)\n", + "\n", + " plt.close(f\"E2E type breakdown histograms {name}\")\n", + " fig, axes = plt.subplots(1, 3, num=f\"E2E type breakdown histograms {name}\", dpi=300, figsize=(16, 9))\n", + " fig.suptitle(f\"E2E Latency Breakdown by Resource Type {name}\")\n", + "\n", + " for type, ax in zip(plot_types, axes):\n", + " durations = [item.duration for item in items if item.type == type]\n", + "\n", + " df = pd.Series(durations)\n", + " df.to_csv(os.path.join(OUT_PATH, f\"plot_e2es_{type}_portion_{name}.csv\"), header=[f\"e2e_latency_{type}_portion_s\"], index=False)\n", + "\n", + " ax.set_title(type)\n", + " ax.hist(durations, bins=50)\n", + " #ax.set_yscale(\"log\")\n", + " ax.set_xlabel(\"Duration [s]\")\n", + " ax.set_ylabel(\"Occurrences\")\n", + "\n", + " return fig\n", + "\n", + " ##################################################\n", + " # Plot DDS/idle/computation time histograms\n", + " # Histograms show individual latency components\n", + " # over all dataflows (de-duplicated)\n", + " ##################################################\n", + "\n", + " fig = e2e_breakdown_type_hist__(conv_items_unique)\n", + " plt.savefig(os.path.join(OUT_PATH, f\"plot_e2e_portions_{name}.png\"))\n", + "\n", + " ##################################################\n", + " # Plot histogram of all E2E latencies observed\n", + " ##################################################\n", + "\n", + " e2es = [path[-1].timestamp - path[0].timestamp for path in relevant_dataflows]\n", + "\n", + " df = pd.Series(e2es)\n", + " df.to_csv(os.path.join(OUT_PATH, f\"plot_e2es_{name}.csv\"), index=False, header=[\"e2e_latency_s\"])\n", + "\n", + " plt.close(f\"E2E histogram_{name}\")\n", + " fig, ax = plt.subplots(num=f\"E2E histogram_{name}\", dpi=300, figsize=(16, 9))\n", + " fig.suptitle(f\"E2E Latency Histogram_{name}\")\n", + " ax: plt.Axes\n", + " ax.hist(e2es, bins=30)\n", + " ax.set_xlabel(\"E2E Latency [s]\")\n", + " ax.set_ylabel(\"Occurrences\")\n", + " ax.axvline(np.mean(e2es), c=\"red\", linewidth=2)\n", + " _, max_ylim = ax.get_ylim()\n", + " ax.text(np.mean(e2es) * 1.02, max_ylim * 0.98, 'Mean: {:.3f}s'.format(np.mean(e2es)))\n", + " plt.savefig(os.path.join(OUT_PATH, f\"plot_e2es_{name}.png\"))" ] }, { "cell_type": "code", - "execution_count": null, + "execution_count": 15, "metadata": { "collapsed": false }, @@ -595,11 +166461,22 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 16, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "%%skip_if_false E2E_PLOT\n", @@ -658,11 +166535,22 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 17, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "%%skip_if_false E2E_PLOT\n", @@ -692,11 +166580,53 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 18, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stderr", + "output_type": "stream", + "text": [ + "Calculating breakdowns: 100%|██████████| 500/500 [00:00<00:00, 109135.72it/s]\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "7 7\n" + ] + }, + { + "ename": "ValueError", + "evalue": "zero-size array to reduction operation minimum which has no identity", + "output_type": "error", + "traceback": [ + "\u001b[0;31m---------------------------------------------------------------------------\u001b[0m", + "\u001b[0;31mValueError\u001b[0m Traceback (most recent call last)", + "Cell \u001b[0;32mIn[18], line 30\u001b[0m\n\u001b[1;32m 28\u001b[0m indices \u001b[38;5;241m=\u001b[39m [i \u001b[38;5;28;01mfor\u001b[39;00m i, t \u001b[38;5;129;01min\u001b[39;00m \u001b[38;5;28menumerate\u001b[39m(types) \u001b[38;5;28;01mif\u001b[39;00m t \u001b[38;5;241m==\u001b[39m \u001b[38;5;28mtype\u001b[39m]\n\u001b[1;32m 29\u001b[0m xs \u001b[38;5;241m=\u001b[39m [component_durations[i] \u001b[38;5;28;01mfor\u001b[39;00m i \u001b[38;5;129;01min\u001b[39;00m indices]\n\u001b[0;32m---> 30\u001b[0m vln \u001b[38;5;241m=\u001b[39m \u001b[43max\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mviolinplot\u001b[49m\u001b[43m(\u001b[49m\u001b[43mxs\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mindices\u001b[49m\u001b[43m)\u001b[49m\n\u001b[1;32m 31\u001b[0m add_label(vln, \u001b[38;5;28mtype\u001b[39m)\n\u001b[1;32m 32\u001b[0m \u001b[38;5;28;01mfor\u001b[39;00m i, x \u001b[38;5;129;01min\u001b[39;00m \u001b[38;5;28mzip\u001b[39m(indices, xs):\n", + "File \u001b[0;32m~/dataflow-analysis/venv310/lib/python3.10/site-packages/matplotlib/_api/deprecation.py:453\u001b[0m, in \u001b[0;36mmake_keyword_only..wrapper\u001b[0;34m(*args, **kwargs)\u001b[0m\n\u001b[1;32m 447\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m \u001b[38;5;28mlen\u001b[39m(args) \u001b[38;5;241m>\u001b[39m name_idx:\n\u001b[1;32m 448\u001b[0m warn_deprecated(\n\u001b[1;32m 449\u001b[0m since, message\u001b[38;5;241m=\u001b[39m\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mPassing the \u001b[39m\u001b[38;5;132;01m%(name)s\u001b[39;00m\u001b[38;5;124m \u001b[39m\u001b[38;5;132;01m%(obj_type)s\u001b[39;00m\u001b[38;5;124m \u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 450\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mpositionally is deprecated since Matplotlib \u001b[39m\u001b[38;5;132;01m%(since)s\u001b[39;00m\u001b[38;5;124m; the \u001b[39m\u001b[38;5;124m\"\u001b[39m\n\u001b[1;32m 451\u001b[0m \u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mparameter will become keyword-only in \u001b[39m\u001b[38;5;132;01m%(removal)s\u001b[39;00m\u001b[38;5;124m.\u001b[39m\u001b[38;5;124m\"\u001b[39m,\n\u001b[1;32m 452\u001b[0m name\u001b[38;5;241m=\u001b[39mname, obj_type\u001b[38;5;241m=\u001b[39m\u001b[38;5;124mf\u001b[39m\u001b[38;5;124m\"\u001b[39m\u001b[38;5;124mparameter of \u001b[39m\u001b[38;5;132;01m{\u001b[39;00mfunc\u001b[38;5;241m.\u001b[39m\u001b[38;5;18m__name__\u001b[39m\u001b[38;5;132;01m}\u001b[39;00m\u001b[38;5;124m()\u001b[39m\u001b[38;5;124m\"\u001b[39m)\n\u001b[0;32m--> 453\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m \u001b[43mfunc\u001b[49m\u001b[43m(\u001b[49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[43margs\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[43mkwargs\u001b[49m\u001b[43m)\u001b[49m\n", + "File \u001b[0;32m~/dataflow-analysis/venv310/lib/python3.10/site-packages/matplotlib/__init__.py:1521\u001b[0m, in \u001b[0;36m_preprocess_data..inner\u001b[0;34m(ax, data, *args, **kwargs)\u001b[0m\n\u001b[1;32m 1518\u001b[0m \u001b[38;5;129m@functools\u001b[39m\u001b[38;5;241m.\u001b[39mwraps(func)\n\u001b[1;32m 1519\u001b[0m \u001b[38;5;28;01mdef\u001b[39;00m \u001b[38;5;21minner\u001b[39m(ax, \u001b[38;5;241m*\u001b[39margs, data\u001b[38;5;241m=\u001b[39m\u001b[38;5;28;01mNone\u001b[39;00m, \u001b[38;5;241m*\u001b[39m\u001b[38;5;241m*\u001b[39mkwargs):\n\u001b[1;32m 1520\u001b[0m \u001b[38;5;28;01mif\u001b[39;00m data \u001b[38;5;129;01mis\u001b[39;00m \u001b[38;5;28;01mNone\u001b[39;00m:\n\u001b[0;32m-> 1521\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m \u001b[43mfunc\u001b[49m\u001b[43m(\u001b[49m\n\u001b[1;32m 1522\u001b[0m \u001b[43m \u001b[49m\u001b[43max\u001b[49m\u001b[43m,\u001b[49m\n\u001b[1;32m 1523\u001b[0m \u001b[43m \u001b[49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[38;5;28;43mmap\u001b[39;49m\u001b[43m(\u001b[49m\u001b[43mcbook\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43msanitize_sequence\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43margs\u001b[49m\u001b[43m)\u001b[49m\u001b[43m,\u001b[49m\n\u001b[1;32m 1524\u001b[0m \u001b[43m \u001b[49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[43m{\u001b[49m\u001b[43mk\u001b[49m\u001b[43m:\u001b[49m\u001b[43m \u001b[49m\u001b[43mcbook\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43msanitize_sequence\u001b[49m\u001b[43m(\u001b[49m\u001b[43mv\u001b[49m\u001b[43m)\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;28;43;01mfor\u001b[39;49;00m\u001b[43m \u001b[49m\u001b[43mk\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mv\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;129;43;01min\u001b[39;49;00m\u001b[43m \u001b[49m\u001b[43mkwargs\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mitems\u001b[49m\u001b[43m(\u001b[49m\u001b[43m)\u001b[49m\u001b[43m}\u001b[49m\u001b[43m)\u001b[49m\n\u001b[1;32m 1526\u001b[0m bound \u001b[38;5;241m=\u001b[39m new_sig\u001b[38;5;241m.\u001b[39mbind(ax, \u001b[38;5;241m*\u001b[39margs, \u001b[38;5;241m*\u001b[39m\u001b[38;5;241m*\u001b[39mkwargs)\n\u001b[1;32m 1527\u001b[0m auto_label \u001b[38;5;241m=\u001b[39m (bound\u001b[38;5;241m.\u001b[39marguments\u001b[38;5;241m.\u001b[39mget(label_namer)\n\u001b[1;32m 1528\u001b[0m \u001b[38;5;129;01mor\u001b[39;00m bound\u001b[38;5;241m.\u001b[39mkwargs\u001b[38;5;241m.\u001b[39mget(label_namer))\n", + "File \u001b[0;32m~/dataflow-analysis/venv310/lib/python3.10/site-packages/matplotlib/axes/_axes.py:8615\u001b[0m, in \u001b[0;36mAxes.violinplot\u001b[0;34m(self, dataset, positions, vert, orientation, widths, showmeans, showextrema, showmedians, quantiles, points, bw_method, side)\u001b[0m\n\u001b[1;32m 8612\u001b[0m kde \u001b[38;5;241m=\u001b[39m mlab\u001b[38;5;241m.\u001b[39mGaussianKDE(X, bw_method)\n\u001b[1;32m 8613\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m kde\u001b[38;5;241m.\u001b[39mevaluate(coords)\n\u001b[0;32m-> 8615\u001b[0m vpstats \u001b[38;5;241m=\u001b[39m \u001b[43mcbook\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mviolin_stats\u001b[49m\u001b[43m(\u001b[49m\u001b[43mdataset\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43m_kde_method\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mpoints\u001b[49m\u001b[38;5;241;43m=\u001b[39;49m\u001b[43mpoints\u001b[49m\u001b[43m,\u001b[49m\n\u001b[1;32m 8616\u001b[0m \u001b[43m \u001b[49m\u001b[43mquantiles\u001b[49m\u001b[38;5;241;43m=\u001b[39;49m\u001b[43mquantiles\u001b[49m\u001b[43m)\u001b[49m\n\u001b[1;32m 8617\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m \u001b[38;5;28mself\u001b[39m\u001b[38;5;241m.\u001b[39mviolin(vpstats, positions\u001b[38;5;241m=\u001b[39mpositions, vert\u001b[38;5;241m=\u001b[39mvert,\n\u001b[1;32m 8618\u001b[0m orientation\u001b[38;5;241m=\u001b[39morientation, widths\u001b[38;5;241m=\u001b[39mwidths,\n\u001b[1;32m 8619\u001b[0m showmeans\u001b[38;5;241m=\u001b[39mshowmeans, showextrema\u001b[38;5;241m=\u001b[39mshowextrema,\n\u001b[1;32m 8620\u001b[0m showmedians\u001b[38;5;241m=\u001b[39mshowmedians, side\u001b[38;5;241m=\u001b[39mside)\n", + "File \u001b[0;32m~/dataflow-analysis/venv310/lib/python3.10/site-packages/matplotlib/cbook.py:1509\u001b[0m, in \u001b[0;36mviolin_stats\u001b[0;34m(X, method, points, quantiles)\u001b[0m\n\u001b[1;32m 1506\u001b[0m stats \u001b[38;5;241m=\u001b[39m {}\n\u001b[1;32m 1508\u001b[0m \u001b[38;5;66;03m# Calculate basic stats for the distribution\u001b[39;00m\n\u001b[0;32m-> 1509\u001b[0m min_val \u001b[38;5;241m=\u001b[39m \u001b[43mnp\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mmin\u001b[49m\u001b[43m(\u001b[49m\u001b[43mx\u001b[49m\u001b[43m)\u001b[49m\n\u001b[1;32m 1510\u001b[0m max_val \u001b[38;5;241m=\u001b[39m np\u001b[38;5;241m.\u001b[39mmax(x)\n\u001b[1;32m 1511\u001b[0m quantile_val \u001b[38;5;241m=\u001b[39m np\u001b[38;5;241m.\u001b[39mpercentile(x, \u001b[38;5;241m100\u001b[39m \u001b[38;5;241m*\u001b[39m q)\n", + "File \u001b[0;32m~/dataflow-analysis/venv310/lib/python3.10/site-packages/numpy/_core/fromnumeric.py:3302\u001b[0m, in \u001b[0;36mmin\u001b[0;34m(a, axis, out, keepdims, initial, where)\u001b[0m\n\u001b[1;32m 3190\u001b[0m \u001b[38;5;129m@array_function_dispatch\u001b[39m(_min_dispatcher)\n\u001b[1;32m 3191\u001b[0m \u001b[38;5;28;01mdef\u001b[39;00m \u001b[38;5;21mmin\u001b[39m(a, axis\u001b[38;5;241m=\u001b[39m\u001b[38;5;28;01mNone\u001b[39;00m, out\u001b[38;5;241m=\u001b[39m\u001b[38;5;28;01mNone\u001b[39;00m, keepdims\u001b[38;5;241m=\u001b[39mnp\u001b[38;5;241m.\u001b[39m_NoValue, initial\u001b[38;5;241m=\u001b[39mnp\u001b[38;5;241m.\u001b[39m_NoValue,\n\u001b[1;32m 3192\u001b[0m where\u001b[38;5;241m=\u001b[39mnp\u001b[38;5;241m.\u001b[39m_NoValue):\n\u001b[1;32m 3193\u001b[0m \u001b[38;5;124;03m\"\"\"\u001b[39;00m\n\u001b[1;32m 3194\u001b[0m \u001b[38;5;124;03m Return the minimum of an array or minimum along an axis.\u001b[39;00m\n\u001b[1;32m 3195\u001b[0m \n\u001b[0;32m (...)\u001b[0m\n\u001b[1;32m 3300\u001b[0m \u001b[38;5;124;03m 6\u001b[39;00m\n\u001b[1;32m 3301\u001b[0m \u001b[38;5;124;03m \"\"\"\u001b[39;00m\n\u001b[0;32m-> 3302\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m \u001b[43m_wrapreduction\u001b[49m\u001b[43m(\u001b[49m\u001b[43ma\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mnp\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mminimum\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;124;43m'\u001b[39;49m\u001b[38;5;124;43mmin\u001b[39;49m\u001b[38;5;124;43m'\u001b[39;49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43maxis\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;28;43;01mNone\u001b[39;49;00m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mout\u001b[49m\u001b[43m,\u001b[49m\n\u001b[1;32m 3303\u001b[0m \u001b[43m \u001b[49m\u001b[43mkeepdims\u001b[49m\u001b[38;5;241;43m=\u001b[39;49m\u001b[43mkeepdims\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43minitial\u001b[49m\u001b[38;5;241;43m=\u001b[39;49m\u001b[43minitial\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mwhere\u001b[49m\u001b[38;5;241;43m=\u001b[39;49m\u001b[43mwhere\u001b[49m\u001b[43m)\u001b[49m\n", + "File \u001b[0;32m~/dataflow-analysis/venv310/lib/python3.10/site-packages/numpy/_core/fromnumeric.py:86\u001b[0m, in \u001b[0;36m_wrapreduction\u001b[0;34m(obj, ufunc, method, axis, dtype, out, **kwargs)\u001b[0m\n\u001b[1;32m 83\u001b[0m \u001b[38;5;28;01melse\u001b[39;00m:\n\u001b[1;32m 84\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m reduction(axis\u001b[38;5;241m=\u001b[39maxis, out\u001b[38;5;241m=\u001b[39mout, \u001b[38;5;241m*\u001b[39m\u001b[38;5;241m*\u001b[39mpasskwargs)\n\u001b[0;32m---> 86\u001b[0m \u001b[38;5;28;01mreturn\u001b[39;00m \u001b[43mufunc\u001b[49m\u001b[38;5;241;43m.\u001b[39;49m\u001b[43mreduce\u001b[49m\u001b[43m(\u001b[49m\u001b[43mobj\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43maxis\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mdtype\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[43mout\u001b[49m\u001b[43m,\u001b[49m\u001b[43m \u001b[49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[38;5;241;43m*\u001b[39;49m\u001b[43mpasskwargs\u001b[49m\u001b[43m)\u001b[49m\n", + "\u001b[0;31mValueError\u001b[0m: zero-size array to reduction operation minimum which has no identity" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "%%skip_if_false E2E_PLOT\n", @@ -751,7 +166681,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 19, "metadata": { "collapsed": false }, @@ -767,7 +166697,7 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 20, "metadata": { "collapsed": false }, @@ -784,11 +166714,22 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 21, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], "source": [ "%%skip_if_false E2E_ENABLED\n", "%%skip_if_false E2E_PLOT\n", @@ -803,11 +166744,19 @@ }, { "cell_type": "code", - "execution_count": null, + "execution_count": 22, "metadata": { "collapsed": false }, - "outputs": [], + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Done.\n" + ] + } + ], "source": [ "print(\"Done.\")" ] @@ -815,7 +166764,7 @@ ], "metadata": { "kernelspec": { - "display_name": "Python 3", + "display_name": "venv310", "language": "python", "name": "python3" }, @@ -829,12 +166778,7 @@ "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", - "version": "3.11.2" - }, - "vscode": { - "interpreter": { - "hash": "05f7383eaeac09627c87490e6082687b3d1e289dc07cdd1800656e06d52425e4" - } + "version": "3.10.12" } }, "nbformat": 4,